Package Summary
Tags | No category tags. |
Version | 1.12.0 |
License | Apache 2 |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Description | autoware src learn and recode. |
Checkout URI | https://github.com/is-whale/autoware_learn.git |
VCS Type | git |
VCS Version | 1.14 |
Last Updated | 2025-03-14 |
Dev Status | UNKNOWN |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Takamasa Horibe
Authors
- Takamasa Horibe
MPC follower description
Overview
A waypoint follower based on model predictive control (MPC) for accurate path tracking. This can be used as a waypoint_follower, as well as other path following nodes like pure_pursuit.
There are 2 nodes related to MPC follower.
-
/mpc_waypoint_converter
: converts/final_waypoints
to/mpc_waypoints
which includes waypoints behind the self position. This is to solve temporary conflict of planning system and mpc follower so that mpc follower can be used in the same way as pure_pursuit. This will be removed in a future release. -
/mpc_follower
: generates control command (/twist_raw
or/and/ctrl_raw
) to follow/mpc_waypoints
.
Video : comparison of pure_pursuit and mpc_follower with gazebo simulation.
Input and Output for mpc_follower
- input
- /mpc_waypoints : reference waypoints (generated in mpc_waypoints_converter)
- /current_pose : self pose
- /vehicle_status : vehicle information (as velocity and steering angle source)
- output
- /twist_raw : command for vehicle
- /ctrl_raw : command for vehicle
node graph
Parameter description
Notation
The default parameters are adjusted to the Autonomoustuff Lexus RX 450h for under 40 km/h driving.
overall
Name | Type | Description | Default value |
---|---|---|---|
show_debug_info | bool | display debug info | false |
ctrl_period | double | control period [s] | 0.03 |
traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 |
enable_path_smoothing | bool | path smoothing flag. This should be true when uses path resampling to reduce resampling noise. | true |
enable_yaw_recalculation | bool | recalculate yaw angle after resampling. Set true if yaw in received waypoints is noisy. | false |
path_filter_moving_ave_num | int | number of data points moving average filter for path smoothing | 35 |
path_smoothing_times | int | number of times of applying path smoothing filter | 1 |
curvature_smoothing_num | double | index distance of points used in curvature calculation: p(i-num), p(i), p(i+num). larger num makes less noisy values. | 35 |
steering_lpf_cutoff_hz | double | cutoff frequency of lowpass filter for steering output command [hz] | 3.0 |
admisible_position_error | double | stop vehicle when following position error is larger than this value [m]. | 5.0 |
admisible_yaw_error_deg | double | stop vehicle when following yaw angle error is larger than this value [deg]. | 90.0 |
mpc algorithm
Name | Type | Description | Default value |
---|---|---|---|
qp_solver_type | string | QP solver option. described below in detail. | unconstraint_fast |
qpoases_max_iter | int | maximum iteration number for convex optimiaztion with qpoases. | 500 |
vehicle_model_type | string | vehicle model option. described below in detail. | kinematics |
prediction_horizon | int | total prediction step for MPC | 70 |
prediction_sampling_time | double | prediction period for one step [s] | 0.1 |
weight_lat_error | double | weight for lateral error | 0.1 |
weight_heading_error | double | weight for heading error | 0.0 |
weight_heading_error_squared_vel_coeff | double | weight for heading error * velocity | 5.0 |
weight_steering_input | double | weight for steering error (steer command - reference steer) | 1.0 |
weight_steering_input_squared_vel_coeff | double | weight for steering error (steer command - reference steer) * velocity | 0.25 |
weight_lat_jerk | double | weight for lateral jerk (steer(i) - steer(i-1)) * velocity | 0.0 |
weight_terminal_lat_error | double | terminal cost weight for lateral error | 1.0 |
weight_terminal_heading_error | double | terminal cost weight for heading error | 0.1 |
zero_ff_steer_deg | double | threshold of feedforward angle [deg]. feedforward angle smaller than this value is set to zero. | 2.0 |
vehicle
Name | Type | Description | Default value |
---|---|---|---|
wheelbase | double | wheel base length for vehicle model [m] | 2.9 |
steering_tau | double | steering dynamics time constant (1d approximation) for vehicle model [s] | 0.3 |
steer_lim_deg | double | steering angle limit for vehicle model [deg]. This is also used for QP constraint. | 35.0 |
QP solver type
currently, the options are
- unconstraint : use least square method to solve unconstraint QP with eigen.
- unconstraint_fast : similar to unconstraint. This is faster, but lower accuracy for optimization.
- qpoases_hotstart : use QPOASES with hotstart for constrainted QP.
vehicle model type
- kinematics : bicycle kinematics model with steering 1st-order delay
- kinematics_no_delay : bicycle kinematics model without steering delay
- dynamics : bicycle dynamics model considering slip angle
The kinematics
model are being used as default. Please see the reference[1] for more detail.
how to tune MPC parameters
-
Set appropriate vehicle kinematics parameters
wheelbase
,steering_gear_ratio
, andsteer_lim_deg
. Also check the/vehicle_status
topic has appropriate values (speed: vehicle rear-wheels-center velocity [km/h], angle: steering (tire) angle [rad]). These values give a vehicle information to the controller for path following. Errors in these values cause fundamental tracking error. Whether these values are correct can be confirmed by comparing the angular velocity obtained from the model (/mpc_follower/debug/angvel_from_steer
) and the actual angular velocity (such as/estimate_twist/angular/z
). -
Set appropriate vehicle dynamics parameters of
steering_tau
, which is approximated delay from steering angle command to actual steering angle. -
Set
weight_steering_input
= 1.0,weight_lat_error
= 0.1, and other weights to 0. If the vehicle oscillates when driving with low speed, setweight_lat_error
smaller. -
Adjust other weights. One of the simple way for tuning is to increase
weight_lat_error
until oscillation occurs. If the vehicle is unstable with very smallweight_lat_error
, increase terminal weight :weight_terminal_lat_error
andweight_terminal_heading_error
to improve tracking stability. Largerprediction_horizon
and smallerprediction_sampling_time
is effective for tracking performance, but it is a trade-off between computational costs. Other parameters can be adjusted like below.-
weight_lat_error
: Reduce lateral tracking error. This acts like P gain in PID. -
weight_heading_error
: Make a drive straight. This acts like D gain in PID. -
weight_heading_error_squared_vel_coeff
: Make a drive straight in high speed range. -
weight_steering_input
: Reduce oscillation of tracking. -
weight_steering_input_squared_vel_coeff
: Reduce oscillation of tracking in high speed range. -
weight_lat_jerk
: Reduce lateral jerk. -
weight_terminal_lat_error
: Preferable to set a higher value than normal lateral weightweight_lat_error
for stability. -
weight_terminal_heading_error
: Preferable to set a higher value than normal heading weightweight_heading_error
for stability.
-
# reference
[1] Jarrod M. Snider, “Automatic Steering Methods for Autonomous Automobile Path Tracking”, Robotics Institute, Carnegie Mellon University, February 2009.
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
autoware_build_flags | |
catkin | |
amathutils_lib | |
autoware_health_checker | |
autoware_msgs | |
geometry_msgs | |
roscpp | |
rostest | |
rosunit | |
sensor_msgs | |
std_msgs | |
tf2 | |
tf | |
qpoases_vendor |
System Dependencies
Dependant Packages
Launch files
- launch/mpc_follower.launch
-
- ns [default: /]
- show_debug_info [default: false] — flag to display debug info
- ctrl_period [default: 0.03] — control period [s]
- traj_resample_dist [default: 0.1] — ath resampling interval [m]
- enable_yaw_recalculation [default: true] — flag for recalculation of yaw angle after resampling
- admisible_position_error [default: 5.0] — stop mpc calculation when error is larger than the following value
- admisible_yaw_error_deg [default: 90.0] — stop mpc calculation when error is larger than the following value
- enable_path_smoothing [default: true] — flag for path smoothing
- path_smoothing_times [default: 1] — number of times of applying path smoothing filter
- path_filter_moving_ave_num [default: 35] — param of moving average filter for path smoothing
- curvature_smoothing_num [default: 35] — point-to-point index distance used in curvature calculation : curvature is calculated from three points p(i-num), p(i), p(i+num)
- steering_lpf_cutoff_hz [default: 3.0] — cutoff frequency of lowpass filter for steering command [Hz]
- qp_solver_type [default: unconstraint_fast] — optimization solver type. option is unconstraint_fast, unconstraint, and qpoases_hotstart
- qpoases_max_iter [default: 500] — max iteration number for quadratic programming
- vehicle_model_type [default: kinematics] — vehicle model type for mpc prediction. option is kinematics, kinematics_no_delay, and dynamics
- mpc_prediction_horizon [default: 70] — prediction horizon step
- mpc_prediction_sampling_time [default: 0.1] — prediction horizon period [s]
- mpc_weight_lat_error [default: 0.1] — lateral error weight in matrix Q
- mpc_weight_heading_error [default: 0.0] — heading error weight in matrix Q
- mpc_weight_heading_error_squared_vel_coeff [default: 0.3] — heading error * velocity weight in matrix Q
- mpc_weight_steering_input [default: 1.0] — steering error weight in matrix R
- mpc_weight_steering_input_squared_vel_coeff [default: 0.25] — steering error * velocity weight in matrix R
- mpc_weight_lat_jerk [default: 0.0] — lateral jerk weight in matrix R
- mpc_weight_terminal_lat_error [default: 1.0] — terminal lateral error weight in matrix Q to improve mpc stability
- mpc_weight_terminal_heading_error [default: 0.1] — terminal heading error weight in matrix Q to improve mpc stability
- mpc_zero_ff_steer_deg [default: 2.0] — threshold that feed-forward angle becomes zero
- delay_compensation_time [default: 0.0] — steering input delay time for delay compensation
- vehicle_model_steer_tau [default: 0.3] — steering dynamics time constant (1d approzimation) [s]
- vehicle_model_wheelbase [default: 2.9] — wheel base length [m]
- steer_lim_deg [default: 40.0] — steering angle limit [deg]
- steering_gear_ratio [default: 20.0] — steering gear ratio