Skip to content

Pure Pursuit Controller#

The Pure Pursuit Controller module calculates the steering angle for tracking a desired trajectory using the pure pursuit algorithm. This is used as a lateral controller plugin in the autoware_trajectory_follower_node.

Inputs#

Set the following from the controller_node

  • autoware_planning_msgs/Trajectory : reference trajectory to follow.
  • nav_msgs/Odometry: current ego pose and velocity information

Outputs#

Return LateralOutput which contains the following to the controller node

  • autoware_control_msgs/Lateral: target steering angle
  • LateralSyncData
    • steer angle convergence
  • autoware_planning_msgs/Trajectory: predicted path for ego vehicle

Parameters#

Name Type Description Default Range
ld_velocity_ratio float Velocity ratio for lookahead distance. 2.4 N/A
ld_lateral_error_ratio float Lateral error ratio for lookahead distance. 3.6 N/A
ld_curvature_ratio float Curvature ratio for lookahead distance. 120 N/A
long_ld_lateral_error_threshold float Threshold for lateral error in long lookahead distance. 0.5 N/A
min_lookahead_distance float Minimum lookahead distance. 4.35 N/A
max_lookahead_distance float Maximum lookahead distance. 15 N/A
converged_steer_rad float Steering angle considered as converged. 0.1 N/A
reverse_min_lookahead_distance float Minimum lookahead distance for reversing. 7 N/A
prediction_ds float Prediction step size. 0.3 N/A
prediction_distance_length float Prediction distance length. 21 N/A
resampling_ds float Resampling step size. 0.1 N/A
curvature_calculation_distance float Distance for curvature calculation. 4 N/A
enable_path_smoothing boolean Enable or disable path smoothing. 0 N/A
path_filter_moving_ave_num float Number of points for moving average path filter. 25 N/A
control_period float Control period. 0.03 N/A