Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro jazzy showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro kilted showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro rolling showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
github

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released UNRELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro galactic showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro iron showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro melodic showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange

No version for distro noetic showing humble. Known supported distros are highlighted in the buttons above.
Package symbol

autoware_velocity_smoother package from autoware_core repo

autoware_adapi_adaptors autoware_adapi_specs autoware_core_api autoware_default_adapi autoware_core autoware_component_interface_specs autoware_geography_utils autoware_global_parameter_loader autoware_interpolation autoware_kalman_filter autoware_lanelet2_utils autoware_marker_utils autoware_motion_utils autoware_node autoware_object_recognition_utils autoware_osqp_interface autoware_point_types autoware_qos_utils autoware_qp_interface autoware_signal_processing autoware_trajectory autoware_vehicle_info_utils autoware_core_control autoware_simple_pure_pursuit autoware_core_localization autoware_ekf_localizer autoware_gyro_odometer autoware_localization_util autoware_ndt_scan_matcher autoware_pose_initializer autoware_stop_filter autoware_twist2accel autoware_core_map autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_loader autoware_map_projection_loader autoware_core_perception autoware_euclidean_cluster_object_detector autoware_ground_filter autoware_perception_objects_converter autoware_core_planning autoware_mission_planner autoware_objects_of_interest_marker_interface autoware_path_generator autoware_planning_factor_interface autoware_planning_topic_converter autoware_route_handler autoware_velocity_smoother autoware_behavior_velocity_planner autoware_behavior_velocity_planner_common autoware_behavior_velocity_stop_line_module autoware_motion_velocity_obstacle_stop_module autoware_motion_velocity_planner autoware_motion_velocity_planner_common autoware_core_sensing autoware_crop_box_filter autoware_downsample_filters autoware_gnss_poser autoware_vehicle_velocity_converter autoware_planning_test_manager autoware_pyplot autoware_test_node autoware_test_utils autoware_testing autoware_core_vehicle

ROS Distro
humble

Package Summary

Tags No category tags.
Version 1.4.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Description
Checkout URI https://github.com/autowarefoundation/autoware_core.git
VCS Type git
VCS Version main
Last Updated 2025-10-23
Dev Status DEVELOPED
Released RELEASED
Tags planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Package Description

The autoware_velocity_smoother package

Additional Links

No additional links.

Maintainers

  • Fumiya Watanabe
  • Takamasa Horibe
  • Makoto Kurihara
  • Satoshi Ota
  • Go Sakayori

Authors

  • Takamasa Horibe
  • Fumiya Watanabe
  • Yutaka Shimizu
  • Makoto Kurihara

Velocity Smoother

Purpose

autoware_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 autoware_velocity_smoother because the limitations of the acceleration and the jerk means the smoothness of the velocity profile.

Inner-workings / Algorithms

Flow chart

motion_velocity_smoother_flow

Extract trajectory

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.

Apply external velocity limit

It applies the velocity limit input from the external of autoware_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.

Apply stop approaching velocity

It applies the velocity limit near the stopping point. This function is used to approach near the obstacle or improve the accuracy of stopping.

Apply lateral acceleration limit

It applies the velocity limit to decelerate at the curve. For each point in the trajectory, it will find the maximum velocity, so that the lateral acceleration is under the thresholds defined by lateral_acceleration_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve. The velocity limit is set as not to fall under min_curve_velocity.

Note: velocity limit that requests larger than nominal.jerk is not applied. In other words, even if a sharp curve is planned just in front of the ego, no deceleration is performed.

Apply steering rate limit

It calculates the desired steering angles of trajectory points, and it applies the steering rate limit. For each point in the curve, it will find the maximum velocity that satisfy the steering rate limit defined by steering_angle_rate_limits and velocity_thresholds. If the trajectory speed is larger than the computed max velocity, it will try to decelerate at the curve.

Resample trajectory

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.

Calculate initial state

Calculate initial values for velocity planning. The initial values are calculated according to the situation as shown in the following table.

Situation Initial velocity Initial acceleration
First calculation Current velocity 0.0
Engaging engage_velocity engage_acceleration
Deviate between the planned velocity and the current velocity Current velocity Previous planned value
Normal Previous planned value Previous planned value

Smooth 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.

JerkFiltered

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.

L2

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.

Linf

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.

Post process

It performs the post-process of the planned velocity.

  • Set zero velocity ahead of the stopping point
  • Set maximum velocity given in the config named max_velocity
  • Set velocity behind the current pose
  • Resample trajectory (post resampling)
  • Output debug data

After the optimization, a resampling called post resampling is performed before passing the optimized trajectory to the next node. Since the required path interval from optimization may be different from the one for the next module, post resampling helps to fill this gap. Therefore, in post resampling, it is necessary to check the path specification of the following module to determine the parameters. Note that if the computational load of the optimization algorithm is high and the path interval is sparser than the path specification of the following module in the first resampling, post resampling would resample the trajectory densely. On the other hand, if the computational load of the optimization algorithm is small and the path interval is denser than the path specification of the following module in the first resampling, the path is sparsely resampled according to the specification of the following module.

Inputs / Outputs

Input

Name Type Description
~/input/trajectory autoware_planning_msgs/Trajectory Reference trajectory
/planning/scenario_planning/max_velocity std_msgs/Float32 External velocity limit [m/s]
/localization/kinematic_state nav_msgs/Odometry Current odometry

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package autoware_velocity_smoother

1.1.0 (2025-05-01)

1.4.0 (2025-08-11)

  • Merge remote-tracking branch 'origin/main' into humble

  • feat: change planning output topic name to /planning/trajectory (#602)

    • change planning output topic name to /planning/trajectory

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>

  • fix(autoware_mission_planner, velocity_smoother): use transient_local for operation_mode_state (#598) subscribe transient_local with transient_local

  • chore: bump version to 1.3.0 (#554)

  • refactor: implement varying lateral acceleration and steering rate threshold in velocity smoother (#531)

    • refactor: implement varying steering rate threshold in velocity smoother
    • feat: implement varying lateral acceleration limit
    • fix typo in readme
    • fix bugs in unit conversion

    * clean up the obsolete parameter in core planning launch ---------Co-authored-by: Shumpei Wakabayashi <<42209144+shmpwk@users.noreply.github.com>>

  • Contributors: Kem (TiankuiXian), Ryohsuke Mitsudome, Yukihiro Saito, Yuxuan Liu

1.3.0 (2025-06-23)

  • fix: to be consistent version in all package.xml(s)

  • fix: tf2 uses hpp headers in rolling (and is backported) (#483)

    • tf2 uses hpp headers in rolling (and is backported)

    * fixup! tf2 uses hpp headers in rolling (and is backported) ---------

  • chore: bump up version to 1.1.0 (#462) (#464)

  • fix(velocity_smoother): prevent access when vector is empty (#438) add empty check

  • fix(autoware_velocity_smoother): fix deprecated autoware_utils header (#424)

    • fix autoware_utils header
    • style(pre-commit): autofix
    • add header for timekeeper

    * style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • Contributors: Masaki Baba, Mitsuhiro Sakamoto, Tim Clephas, Yutaka Kondo, github-actions

1.0.0 (2025-03-31)

  • chore: update version in package.xml
  • feat(autoware_velocity_smoother): port the package from Autoware Universe (#299)
  • Contributors: Ryohsuke Mitsudome

Launch files

  • launch/velocity_smoother.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_common.param.yaml]
      • nearest_search_param_path
      • input_trajectory [default: /planning/scenario_planning/scenario_selector/trajectory]
      • output_trajectory [default: /planning/trajectory]
      • publish_debug_trajs [default: false]
      • velocity_smoother_type [default: JerkFiltered]
      • param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/default_velocity_smoother.param.yaml]
      • velocity_smoother_param_path [default: $(find-pkg-share autoware_velocity_smoother)/config/$(var velocity_smoother_type).param.yaml]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_velocity_smoother at Robotics Stack Exchange