Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_obstacle_cruise_module at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-10-23 |
Dev Status | UNKNOWN |
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
Additional Links
Maintainers
- Takayuki Murooka
- Yuki Takagi
- Maxime Clement
- Takumi Odashima
Authors
Obstacle Cruise
Role
The obstacle_cruise
module does the cruise planning against a dynamic obstacle in front of the ego.
Activation
This module is activated if the launch parameter launch_obstacle_cruise_module
is set to true.
Inner-workings / Algorithms
Obstacle Filtering
The obstacles meeting the following condition are determined as obstacles for cruising.
-
The lateral distance from the object to the ego’s trajectory is smaller than
obstacle_filtering.max_lat_margin
. - The object type is for cruising according to
obstacle_filtering.object_type.*
. - The object is not crossing the ego’s trajectory (*1).
- If the object is inside the trajectory.
- The object type is for inside cruising according to
obstacle_filtering.object_type.inside.*
. - The object velocity is larger than
obstacle_filtering.obstacle_velocity_threshold_from_cruise
.
- The object type is for inside cruising according to
- If the object is outside the trajectory.
- The object type is for outside cruising according to
obstacle_filtering.object_type.outside.*
. - The object velocity is larger than
obstacle_filtering.outside_obstacle.obstacle_velocity_threshold
. - The highest confident predicted path collides with the ego’s trajectory.
- Its collision’s period is larger than
obstacle_filtering.outside_obstacle.ego_obstacle_overlap_time_threshold
.
- The object type is for outside cruising according to
NOTE
*1: Crossing obstacles
Crossing obstacle is the object whose orientation’s yaw angle against the ego’s trajectory is smaller than obstacle_filtering.crossing_obstacle.obstacle_traj_angle_threshold
.
Yield for vehicles that might cut in into the ego’s lane
It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle’s current lane.
The obstacles meeting the following condition are determined as obstacles for yielding (cruising).
- The object type is for cruising according to
obstacle_filtering.object_type.*
and it is moving with a speed greater thanobstacle_filtering.yield.stopped_obstacle_velocity_threshold
. - The object is not crossing the ego’s trajectory (*1).
- There is another object of type
obstacle_filtering.object_type.side_stopped
stopped in front of the moving obstacle. - The lateral distance (using the ego’s trajectory as reference) between both obstacles is less than
obstacle_filtering.yield.max_lat_dist_between_obstacles
- Both obstacles, moving and stopped, are within
obstacle_filtering.yield.lat_distance_threshold
andobstacle_filtering.yield.lat_distance_threshold
+obstacle_filtering.yield.max_lat_dist_between_obstacles
lateral distance from the ego’s trajectory respectively.
If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego’s lane to avoid the stopped obstacle.
Cruise Planning
The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle.
The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation.
\[d_{rss} = v_{ego} t_{idling} + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}} + l_{margin},\]assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle’s deceleration, $v_{ego}$ is the ego’s current velocity, $v_{obstacle}$ is the front obstacle’s current velocity, $a_{ego}$ is the ego’s acceleration, $a_{obstacle}$ is the obstacle’s acceleration, and $l_{margin}$ is the safety margin.
These values are parameterized as follows. Other common values such as ego’s minimum acceleration is defined in common.param.yaml
.
Parameter | Type | Description |
---|---|---|
cruise_planning.idling_time |
double | idling time for the ego to detect the front vehicle starting deceleration [s] |
cruise_planning.min_ego_accel_for_rss |
double | ego’s acceleration for RSS [m/ss] |
cruise_planning.min_object_accel_for_rss |
double | front obstacle’s acceleration for RSS [m/ss] |
cruise_planning.safe_distance_margin |
double | safety margin for RSS [m] |
The detailed formulation is as follows.
\[\begin{align} d_{error} & = d - d_{rss} \\ d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ v_{pid} & = pid(d_{quad, normalized}) \\ v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) \end{align}\]Variable | Description |
---|---|
d |
actual distance to obstacle |
d_{rss} |
ideal distance to obstacle based on RSS |
v_{min, cruise} |
min_cruise_target_vel |
w_{acc} |
output_ratio_during_accel |
lpf(val) |
apply low-pass filter to val
|
pid(val) |
apply pid to val
|
Algorithm selection for cruise planner
Currently, only a PID-based planner is supported. Each planner will be explained in the following.
Parameter | Type | Description |
---|---|---|
option.planning_algorithm |
string | cruise and stop planning algorithm, selected from “pid_base” |
File truncated at 100 lines see the full file
Changelog for package autoware_motion_velocity_obstacle_cruise_module
0.47.0 (2025-08-11)
-
feat: change planning output topic name to /planning/trajectory (#11135)
- 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>
-
style(pre-commit): update to clang-format-20 (#11088) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
docs(obstacle_cruise): align the rss computation documentation with the codes (#11049) docs(obstacle_cruise): align the rss computation documentation with the codes.
-
refactor(obstacle_slowdown_module, obstacle_cruise_module): follow function name change in autoware_core (#10840) change function name
-
Contributors: Mete Fatih Cırıt, Yuki TAKAGI, Yukihiro Saito, Yuxuan Liu
0.46.0 (2025-06-20)
- Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
- feat(autoware_motion_velocity_planner): only wait for required subscriptions (#10732)
- feat(obstacle_stop_module): maintain larger stop distance for opposing traffic (#10647) Changes for RT1-9226
- Contributors: Arjun Jagdish Ram, Ryohsuke Mitsudome, TaikiYamada4
0.45.0 (2025-05-22)
0.44.2 (2025-06-10)
0.44.1 (2025-05-01)
0.44.0 (2025-04-18)
- Merge remote-tracking branch 'origin/main' into humble
- chore(motion_velocity_planner): move common and node packages to core (#10367)
- fix(motion_velocity_obstacle_xxx_module): fix debug topic name (#10322)
- fix(motion_velocity_planner): remove Metric messages (#10342)
- Contributors: Maxime CLEMENT, Ryohsuke Mitsudome, Takayuki Murooka
0.43.0 (2025-03-21)
-
Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
-
chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
-
feat(path_optimizer): additional failure logging and failure mode handling (#10276) MRM when MPT fails
-
feat!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
-
fix(obstacle_cruise_planner): fix obstacle filtering logic (#10232)
- add absolute
* fix find_yield_cruise_obstacles() calling ---------
-
fix(obstacle_cruise_planner): ignore invalid stopping objects (#10227)
- ignore not specified stopping objects
- change debug print level
- add ahead_stopped prameter
* rename ahead_stopped -> side_stopped ---------
-
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |