Autoware Trajectory Optimizer#
The autoware_trajectory_optimizer
package is responsible for generating smooth and feasible trajectories for autonomous vehicles. It takes in a series of waypoints and outputs a continuous trajectory that the vehicle can follow. The interpolation methods for the path include the elastic band smoother and the Akima spline. Additionally, velocity smoothing can be achieved using assets from the autoware_velocity_smoother
package.
Features#
- Interpolates waypoints to generate smooth trajectories.
- Ensures continuity and feasibility of the generated trajectories.
- Configurable parameters to adjust the interpolation behavior.
Dependencies#
This package depends on the following packages:
autoware_velocity_smoother
: Ensures that the velocity profile of the trajectory is smooth and feasible.autoware_path_smoother
: Smooths the path to ensure that the trajectory is continuous and drivable.
Parameters#
Name | Type | Description | Default | Range |
---|---|---|---|---|
nearest_dist_threshold_m | float | Constraint used to search for the nearest trajectory pose to the ego vehicle [m] | 1.5 | ≥0 |
nearest_yaw_threshold_rad | float | Constraint used to search for the nearest trajectory pose to the ego vehicle [rad] | 1 | ≥0 |
target_pull_out_speed_mps | float | To assure the ego can start moving from a stopped position, this parameter sets a minimum trajectory speed value [m/s] | 1 | ≥0 |
target_pull_out_acc_mps2 | float | To assure the ego can start moving from a stopped position, this parameter sets a minimum trajectory acceleration value [m/s^2] | 1 | ≥0 |
max_speed_mps | float | The maximum allowable velocity for the trajectory [m/s] | 8.33 | ≥0 |
max_lateral_accel_mps2 | float | Maximum lateral acceleration [m/s^2] | 1.5 | ≥0 |
spline_interpolation_resolution_m | float | Interpolation resolution for Akima spline [m] | 0.5 | >0 |
backward_trajectory_extension_m | float | How long should the ego trajectory extend backward. This backward trajectory is built using the ego's previous poses [m] | 5 | ≥0 |
use_akima_spline_interpolation | boolean | To use akima spline interpolation to smooth the trajectories | 1 | N/A |
smooth_trajectories | boolean | Flag to indicate if the Elastic Band smoother should be applied on the input trajectories | 1 | N/A |
limit_speed | boolean | Flag to indicate if a max_speed_mps speed limit should be applied to the trajectories | 1 | N/A |
limit_lateral_acceleration | boolean | Enable lateral acceleration limiting | 1 | N/A |
set_engage_speed | boolean | Set engage speed for trajectory points | 0 | N/A |
fix_invalid_points | boolean | If the module should remove repeated or invalid points, or points that go against the general trajectory direction | 1 | N/A |
smooth_velocities | boolean | Apply velocity smoothing to the input trajectories | 0 | N/A |
extend_trajectory_backward | boolean | Flag used to indicate if the ego's trajectory should be extended backward | 1 | N/A |
jerk_filter_params.jerk_weight | float | Weight for smoothness cost for jerk | 10 | ≥0 |
jerk_filter_params.over_v_weight | float | Weight for over speed limit cost | 100000 | ≥0 |
jerk_filter_params.over_a_weight | float | Weight for over accel limit cost | 5000 | ≥0 |
jerk_filter_params.over_j_weight | float | Weight for over jerk limit cost | 2000 | ≥0 |
jerk_filter_params.jerk_filter_ds | float | Resampling ds for jerk filter [m] | 0.1 | >0 |
common.output_delta_arc_length | float | Delta arc length for output trajectory [m] | 0.5 | >0 |
common.output_backward_traj_length | float | Backward length for backward trajectory from base_link [m] | 5 | ≥0 |
option.enable_warm_start | boolean | Enable warm start for optimization | 1 | N/A |
option.enable_optimization_validation | boolean | Enable optimization validation | 0 | N/A |
common.num_points | integer | Number of points for optimization | 100 | ≥1 |
common.delta_arc_length | float | Delta arc length for optimization [m] | 1 | >0 |
weight.smooth_weight | float | Weight for smoothness constraint | 1 | ≥0 |
weight.lat_error_weight | float | Weight for lateral error constraint | 0.001 | ≥0 |
elastic_band_params.ego_nearest_dist_threshold | float | Distance threshold for ego nearest search [m] | 3 | ≥0 |
elastic_band_params.ego_nearest_yaw_threshold | float | Yaw threshold for ego nearest search [rad] | 1.046 | ≥0 |
Parameters can be set via YAML configuration files in the config/
directory.