Skip to content

Latest commit

 

History

History
86 lines (72 loc) · 5.65 KB

README.md

File metadata and controls

86 lines (72 loc) · 5.65 KB

Trajectory Optimizer

Table of Contents
  1. Disclaimer
  2. Dependencies
  3. Approach
  4. Workflow
  5. Parameters

Formula Student model-based trajectory optimization algorithm. This algorithm is shared as part of my Final Degree Thesis. Developed during the 2021-22 Formula Student season, it's an offline trajectory optimization approach relying on a dynamic bicycle model which is avaluated for the whole midline path in order to find the optimal path. This approach can be seen as a one-time MPC execution with an horizon lenght (or prediction horizon) as long as the given midline.

Disclaimer

This is a tailored motion planning solution developed for CAT14X & CAT15X BCN eMotorsport cars. If you plan to use this algorithm in any Formula Student Competition the only thing I ask for is to ALWAYS REFERENCE the team BCN eMotorsport.

Dependencies

NOTE: CasADi should be built from sources in your /home directory, where this pkg will look for it. If you have installed CasADi somewhere else adapt the CMakeLists.txt before building this pkg.

In order to install casadi from source, follow this tutorial.

When building CasADi from source the Ipopt solver is already included so the Building CasADi from sources section is the only one to follow from the tutorial mentioned above.

Approach

For specific information on how the trajectory optimization procedure is done please read this thesis.

The most important advantage of this optimization algorithm is that it is not based on any geometrical approach, but it tries to find the optimal race line by taking into account the constraints imposed by the dynamic bicycle model. This way, apart from the actual race line, an optimal state for each point of the trajectory is obtained. This means that it also outputs vx, vy and yawrate profiles as well as steering and throttle commands profiles.

FSG2019 track results:

For more results read this.

Workflow

This pkg includes three different nodes (or executables), which are thought to be run in the following order:

  • midline (offline) executable is meant to be executed through midline.launch. It reads the detected cones during a complete run and saves the midline trajectory.
  • optimizer (offline) executable is meant to be executed through optimizer.launch. It reads the midline trajectory, sets up the Optimization Problem and solves it. It saves the results in x_opt file.
  • tro (online) executable is meant to be executed through tro.launch. It's the only node thought to run online. It reads the Optimization Problem solution and computes the optimal trajectory, as well as interpolating the optimal states, before publishing the partial trajectory data to the ROS network.

Parameters

Explanation of all the parameters used:

Parameter Summary Value [SI]
Qs Progress rate weight 1.0
Qslip Slip difference weight 0.1
Rd Steering rate weight 1.4
Ra Acceleration rate weight 0.3
RMtv Additional moment weight 1.0
Bf Pacejka Constant 10.5507
Br Pacejka Constant 10.5507
Cf Pacejka Constant -1.2705
Cr Pacejka Constant -1.2705
Df Pacejka Constant 2208.0635
Dr Pacejka Constant 2563.599
Lf Distance from CoG to front axis 0.708
Lr Distance from CoG to rear axis 0.822
L Total car's length 2.72
W Total car's width 1.5
m Car's mass 210.0
Iz Inertial moment around z axis 180.0
rhoair Air's density 1.255
Aaero Drag area 1.0
Cd Drag coefficient 1.2727
Cmotor Motor Constant (max. N) 4283.4645
Cr Rolling resistance (% of car's weight) 0.45%