motion_velocity_smoother outputs a desired velocity profile on a reference trajectory.
This module plans a velocity profile within the limitations of the velocity, the acceleration and the jerk to realize both the maximization of velocity and the ride quality.
We call this module motion_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.
For the point on the reference trajectory closest to the center of the rear wheel axle of the vehicle, it extracts the reference path between extract_behind_dist behind and extract_ahead_dist ahead.
It applies the velocity limit input from the external of motion_velocity_smoother.
Remark that the external velocity limit is different from the velocity limit already set on the map and the reference trajectory.
The external velocity is applied at the position that it is able to reach the velocity limit with the deceleration and the jerk constraints set as the parameter.
It applies the velocity limit to decelerate at the curve.
It calculate the velocity limit from the curvature of the reference trajectory and the maximum lateral acceleration max_lateral_accel.
The velocity limit is set as not to fall under min_curve_velocity.
It resamples the points on the reference trajectory with designated time interval.
Note that the range of the length of the trajectory is set between min_trajectory_length and max_trajectory_length, and the distance between two points is longer than min_trajectory_interval_distance.
It samples densely up to the distance traveled between resample_time with the current velocity, then samples sparsely after that.
By sampling according to the velocity, both calculation load and accuracy are achieved since it samples finely at low velocity and coarsely at high velocity.
It plans the velocity.
The algorithm of velocity planning is chosen from JerkFiltered, L2 and Linf, and it is set in the launch file.
In these algorithms, they use OSQP[1] as the solver of the optimization.
It minimizes the sum of the minus of the square of the velocity and the square of the violation of the velocity limit, the acceleration limit and the jerk limit.
It minimizes the sum of the minus of the square of the velocity, the square of the the pseudo-jerk[2] and the square of the violation of the velocity limit and the acceleration limit.
It minimizes the sum of the minus of the square of the velocity, the maximum absolute value of the the pseudo-jerk[2] and the square of the violation of the velocity limit and the acceleration limit.
Assume that the velocity limit or the stopping point is properly set at the point on the reference trajectory
If the velocity limit set in the reference path cannot be achieved by the designated constraints of the deceleration and the jerk, decelerate while suppressing the velocity, the acceleration and the jerk deviation as much as possible
The importance of the deviations is set in the config file
[1] B. Stellato, et al., "OSQP: an operator splitting solver for quadratic programs", Mathematical Programming Computation, 2020, 10.1007/s12532-020-00179-2.
[2] Y. Zhang, et al., "Toward a More Complete, Flexible, and Safer Speed Planning for Autonomous Driving via Convex Optimization", Sensors, vol. 18, no. 7, p. 2185, 2018, 10.3390/s18072185