Package Summary
Tags | No category tags. |
Version | 0.43.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-04-09 |
Dev Status | UNKNOWN |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Tomohito Ando
- Makoto Kurihara
- Tomoya Kimura
- Shumpei Wakabayashi
- Takayuki Murooka
- Kosuke Takeuchi
Authors
- Tomohito Ando
Run Out
Role
run_out
is the module that decelerates and stops for dynamic obstacles such as pedestrians, bicycles and motorcycles.
Activation Timing
This module is activated if launch_run_out
becomes true
Inner-workings / Algorithms
Flow chart
@startuml
title modifyPathVelocity
start
partition "Preprocess path" {
:Calculate the expected target velocity for ego vehicle;
:Extend path;
:Trim path from ego position;
}
partition "Preprocess obstacles" {
:Create data of abstracted dynamic obstacles;
:Exclude obstacles outside of partition lanelet;
}
partition "Collision_detection" {
:Detect collision with dynamic obstacles;
}
partition "Insert velocity" {
:Insert velocity to decelerate for obstacles;
:Limit velocity with specified jerk and acc limit;
}
stop
@enduml
Preprocess path
Calculate the expected target velocity for ego vehicle
Calculate the expected target velocity for the ego vehicle path to calculate time to collision with obstacles more precisely. The expected target velocity is calculated with autoware velocity smoother module by using current velocity, current acceleration and velocity limits directed by the map and external API.
Extend the path
The path is extended by the length of base link to front to consider obstacles after the goal.
Trim path from ego position
The path is trimmed from ego position to a certain distance to reduce calculation time.
Trimmed distance is specified by parameter of detection_distance
.
Preprocess obstacles
Create data of abstracted dynamic obstacle
This module can handle multiple types of obstacles by creating abstracted dynamic obstacle data layer. Currently we have 3 types of detection method (Object, ObjectWithoutPath, Points) to create abstracted obstacle data.
Abstracted dynamic obstacle
Abstracted obstacle data has following information.
Name | Type | Description |
---|---|---|
pose | geometry_msgs::msg::Pose |
pose of the obstacle |
classifications | std::vector<autoware_perception_msgs::msg::ObjectClassification> |
classifications with probability |
shape | autoware_perception_msgs::msg::Shape |
shape of the obstacle |
predicted_paths | std::vector<DynamicObstacle::PredictedPath> |
predicted paths with confidence. this data doesn’t have time step because we use minimum and maximum velocity instead. |
min_velocity_mps | float |
minimum velocity of the obstacle. specified by parameter of dynamic_obstacle.min_vel_kmph
|
max_velocity_mps | float |
maximum velocity of the obstacle. specified by parameter of dynamic_obstacle.max_vel_kmph
|
Enter the maximum/minimum velocity of the object as a parameter, adding enough margin to the expected velocity. This parameter is used to create polygons for collision detection.
Future work: Determine the maximum/minimum velocity from the estimated velocity with covariance of the object
3 types of detection method
We have 3 types of detection method to meet different safety and availability requirements. The characteristics of them are shown in the table below.
Method of Object
has high availability (less false positive) because it detects only objects whose predicted path is on the lane. However, sometimes it is not safe because perception may fail to detect obstacles or generate incorrect predicted paths.
On the other hand, method of Points
has high safety (less false negative) because it uses pointcloud as input. Since points don’t have a predicted path, the path that moves in the direction normal to the path of ego vehicle is considered to be the predicted path of abstracted dynamic obstacle data. However, without proper adjustment of filter of points, it may detect a lot of points and it will result in very low availability.
Method of ObjectWithoutPath
has the characteristics of an intermediate of Object
and Points
.
Method | Description |
---|---|
Object | use an object with the predicted path for collision detection. |
ObjectWithoutPath | use an object but not use the predicted path for collision detection. replace the path assuming that an object jumps out to the lane at specified velocity. |
Points | use filtered points for collision detection. the path is created assuming that points jump out to the lane. points are regarded as an small circular shaped obstacle. |
Exclude obstacles outside of partition
This module can exclude the obstacles outside of partition such as guardrail, fence, and wall.
We need lanelet map that has the information of partition to use this feature.
By this feature, we can reduce unnecessary deceleration by obstacles that are unlikely to jump out to the lane.
You can choose whether to use this feature by parameter of use_partition_lanelet
.
Exclude obstacles by label
This module only acts on target obstacles defined by the target_obstacle_types
parameter. If an obstacle of a type not specified by said parameter is detected, it will be ignored by this module.
Exclude obstacles that are already on the ego vehicle’s path
In the cases were an obstacle is already on the ego vehicle’s path, it cannot “cut in” into the ego’s path anymore (which is the situation this module tries to handle) so it might be useful to exclude obstacles already on the vehicle’s footprint path. By setting the parameter exclude_obstacles_already_in_path
to true, this module will exclude the obstacles that are considered to be already on the ego vehicle’s path for more than keep_obstacle_on_path_time_threshold
. The module considers the ego vehicle’s closest path point to each obstacle’s current position, and determines the lateral distance between the obstacle and the right and left sides of the ego vehicle. If the obstacle is located within the left and right extremes of the vehicle for that pose, then it is considered to be inside the ego vehicle’s footprint path and it is excluded. The virtual width of the vehicle used to detect if an obstacle is within the path or not, can be adjusted by the ego_footprint_extra_margin
parameter.
Exclude obstacles that cross the ego vehicle’s “cut line”
This module can exclude obstacles that have predicted paths that will cross the back side of the ego vehicle. It excludes obstacles if their predicted path crosses the ego’s “cut line”. The “cut line” is a virtual line segment that is perpendicular to the ego vehicle and that passes through the ego’s base link.
You can choose whether to use this feature by setting the parameter use_ego_cut_line
to true
or false
. The width of the line can be tuned with the parameter ego_cut_line_length
.
Collision detection
Detect collision with dynamic obstacles
Along the ego vehicle path, determine the points where collision detection is to be performed for each detection_span
.
The travel times to the each points are calculated from the expected target velocity.
For the each points, collision detection is performed using the footprint polygon of the ego vehicle and the polygon of the predicted location of the obstacles.
The predicted location of the obstacles is described as rectangle or polygon that has the range calculated by min velocity, max velocity and the ego vehicle’s travel time to the point.
If the input type of the dynamic obstacle is Points
, the obstacle shape is defined as a small cylinder.
Multiple points are detected as collision points because collision detection is calculated between two polygons. So we select the point that is on the same side as the obstacle and close to ego vehicle as the collision point.
Insert velocity
Insert velocity to decelerate for obstacles
If the collision is detected, stop point is inserted on distance of base link to front + stop margin from the selected collision point. The base link to front means the distance between base_link (center of rear-wheel axis) and front of the car. Stop margin is determined by the parameter of stop_margin
.
Insert velocity to approach the obstacles
If you select the method of Points
or ObjectWithoutPath
, sometimes ego keeps stopping in front of the obstacle.
To avoid this problem, This feature has option to approach the obstacle with slow velocity after stopping.
If the parameter of approaching.enable
is set to true, ego will approach the obstacle after ego stopped for state.stop_time_thresh
seconds.
The maximum velocity of approaching can be specified by the parameter of approaching.limit_vel_kmph
.
The decision to approach the obstacle is determined by a simple state transition as following image.
@startuml
hide empty description
left to right direction
title State transition for approaching the obstacle
[*] --> GO
GO --> STOP : Current velocity is less than threshold
STOP --> GO : Current velocity is larger than threshold
STOP --> APPROACH : Stop duration is larger than threshold
APPROACH --> GO : There are no obstacles or \n distance to the obstacle is larger than threshold
APPROACH --> APPROACH : Approach duration is less than threshold
@enduml
Limit velocity with specified jerk and acc limit
The maximum slowdown velocity is calculated in order not to slowdown too much.
See the Occlusion Spot document for more details.
You can choose whether to use this feature by parameter of slow_down_limit.enable
.
Module Parameters
Parameter | Type | Description |
---|---|---|
detection_method |
string | [-] candidate: Object, ObjectWithoutPath, Points |
target_obstacle_types |
vector of string | [-] specifies which obstacle types will be considered by the module, if the obstacles classification type is not written here, it will be ignored. candidate: [“PEDESTRIAN”, “BICYCLE”,”MOTORCYCLE”] |
use_partition_lanelet |
bool | [-] whether to use partition lanelet map data |
specify_decel_jerk |
bool | [-] whether to specify jerk when ego decelerates |
stop_margin |
double | [m] the vehicle decelerates to be able to stop with this margin |
passing_margin |
double | [m] the vehicle begins to accelerate if the vehicle’s front in predicted position is ahead of the obstacle + this margin |
deceleration_jerk |
double | [m/s^3] ego decelerates with this jerk when stopping for obstacles |
detection_distance |
double | [m] ahead distance from ego to detect the obstacles |
detection_span |
double | [m] calculate collision with this span to reduce calculation time |
min_vel_ego_kmph |
double | [km/h] min velocity to calculate time to collision |
Parameter /detection_area | Type | Description |
---|---|---|
margin_ahead |
double | [m] ahead margin for detection area polygon |
margin_behind |
double | [m] behind margin for detection area polygon |
Parameter /dynamic_obstacle | Type | Description |
---|---|---|
use_mandatory_area |
double | [-] whether to use mandatory detection area |
assume_fixed_velocity.enable |
double | [-] If enabled, the obstacle’s velocity is assumed to be within the minimum and maximum velocity values specified below |
assume_fixed_velocity.min_vel_kmph |
double | [km/h] minimum velocity for dynamic obstacles |
assume_fixed_velocity.max_vel_kmph |
double | [km/h] maximum velocity for dynamic obstacles |
diameter |
double | [m] diameter of obstacles. used for creating dynamic obstacles from points |
height |
double | [m] height of obstacles. used for creating dynamic obstacles from points |
max_prediction_time |
double | [sec] create predicted path until this time |
time_step |
double | [sec] time step for each path step. used for creating dynamic obstacles from points or objects without path |
points_interval |
double | [m] divide obstacle points into groups with this interval, and detect only lateral nearest point. used only for Points method |
Parameter /approaching | Type | Description |
---|---|---|
enable |
bool | [-] whether to enable approaching after stopping |
margin |
double | [m] distance on how close ego approaches the obstacle |
limit_vel_kmph |
double | [km/h] limit velocity for approaching after stopping |
Parameter /state | Type | Description |
---|---|---|
stop_thresh |
double | [m/s] threshold to decide if ego is stopping |
stop_time_thresh |
double | [sec] threshold for stopping time to transit to approaching state |
disable_approach_dist |
double | [m] end the approaching state if distance to the obstacle is longer than this value |
keep_approach_duration |
double | [sec] keep approach state for this duration to avoid chattering of state transition |
Parameter /slow_down_limit | Type | Description |
---|---|---|
enable |
bool | [-] whether to enable to limit velocity with max jerk and acc |
max_jerk |
double | [m/s^3] minimum jerk deceleration for safe brake. |
max_acc |
double | [m/s^2] minimum accel deceleration for safe brake. |
Parameter /ignore_momentary_detection | Type | Description |
---|---|---|
enable |
bool | [-] whether to ignore momentary detection |
time_threshold |
double | [sec] ignores detections that persist for less than this duration |
Future extensions / Unimplemented parts
- Calculate obstacle’s min velocity and max velocity from covariance
- Detect collisions with polygon object
- Handle the case when the predicted path of obstacles are not straight line
- Currently collision check is calculated based on the assumption that the predicted path of the obstacle is a straight line
Changelog for package autoware_behavior_velocity_run_out_module
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)
- fix(behavior_velocity_planner): planning factor integration
(#10292)
- fix: blind_spot
- fix: crosswalk
- fix: detection_area
- fix: intersection
- fix: no_drivable_lane
- fix: no_stopping_area
- fix: run_out
- fix: stop_line
- fix: traffic_light
- fix: virtual_traffic_light
* fix: walk_way ---------
- feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
- Contributors: Hayato Mizushima, Satoshi OTA, Yutaka Kondo, 心刚
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
- fix: add missing includes to autoware_universe_utils (#10091)
- fix(behavior_velocity_run_out_module): fix slow_down jerk filter (#10065)
- feat!: replace tier4_planning_msgs/PathWithLaneId with autoware_internal_planning_msgs/PathWithLaneId (#10023)
- feat(planning_test_manager): abstract message-specific functions
(#9882)
- abstract message-specific functions
- include necessary header
- adapt velocity_smoother to new test manager
- adapt behavior_velocity_planner to new test manager
- adapt path_optimizer to new test manager
- fix output subscription
- adapt behavior_path_planner to new test manager
- adapt scenario_selector to new test manager
- adapt freespace_planner to new test manager
- adapt planning_validator to new test manager
- adapt obstacle_stop_planner to new test manager
- adapt obstacle_cruise_planner to new test manager
- disable test for freespace_planner
- adapt behavior_velocity_crosswalk_module to new test manager
- adapt behavior_path_lane_change_module to new test manager
- adapt behavior_path_avoidance_by_lane_change_module to new test manager
- adapt behavior_path_dynamic_obstacle_avoidance_module to new test manager
- adapt behavior_path_external_request_lane_change_module to new test manager
- adapt behavior_path_side_shift_module to new test manager
- adapt behavior_path_static_obstacle_avoidance_module to new test manager
- adapt path_smoother to new test manager
- adapt behavior_velocity_blind_spot_module to new test manager
- adapt behavior_velocity_detection_area_module to new test manager
- adapt behavior_velocity_intersection_module to new test manager
- adapt behavior_velocity_no_stopping_area_module to new test manager
- adapt behavior_velocity_run_out_module to new test manager
- adapt behavior_velocity_stop_line_module to new test manager
- adapt behavior_velocity_traffic_light_module to new test manager
- adapt behavior_velocity_virtual_traffic_light_module to new test manager
- adapt behavior_velocity_walkway_module to new test manager
- adapt motion_velocity_planner_node_universe to new test manager
- include necessary headers
* Odometries -> Odometry ---------Co-authored-by: Takayuki Murooka <<takayuki5168@gmail.com>>
- Contributors: Fumiya Watanabe, Mitsuhiro Sakamoto, Ryohsuke Mitsudome, Tomoya Kimura, 心刚
0.41.2 (2025-02-19)
- chore: bump version to 0.41.1 (#10088)
- Contributors: Ryohsuke Mitsudome
0.41.1 (2025-02-10)
0.41.0 (2025-01-29)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- chore(planning): move package directory for planning factor
interface
(#9948)
- chore: add new package for planning factor interface
- chore(surround_obstacle_checker): update include file
- chore(obstacle_stop_planner): update include file
- chore(obstacle_cruise_planner): update include file
- chore(motion_velocity_planner): update include file
- chore(bpp): update include file
- chore(bvp-common): update include file
- chore(blind_spot): update include file
- chore(crosswalk): update include file
- chore(detection_area): update include file
- chore(intersection): update include file
- chore(no_drivable_area): update include file
- chore(no_stopping_area): update include file
- chore(occlusion_spot): update include file
- chore(run_out): update include file
- chore(speed_bump): update include file
- chore(stop_line): update include file
- chore(template_module): update include file
- chore(traffic_light): update include file
- chore(vtl): update include file
- chore(walkway): update include file
* chore(motion_utils): remove factor interface ---------
- feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (#9927) Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>> Co-authored-by: Ryohsuke Mitsudome <<43976834+mitsudome-r@users.noreply.github.com>> Co-authored-by: satoshi-ota <<satoshi.ota928@gmail.com>>
- feat(behavior_velocity_modules): add node test
(#9790)
- feat(behavior_velocity_crosswalk): add node test
- fix
- feat(behavior_velocity_xxx_module): add node test
- fix
- fix
- fix
- fix
* change directory tests -> test ---------
- refactor(behavior_velocity_planner_common): add
behavior_velocity_rtc_interface and move RTC-related
implementation
(#9799)
- split into planer_common and rtc_interface
* Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp Co-authored-by: Mamoru Sobue <<mamoru.sobue@tier4.jp>> * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp Co-authored-by: Mamoru Sobue <<mamoru.sobue@tier4.jp>> * fix ——
Co-authored-by: Mamoru Sobue <<mamoru.sobue@tier4.jp>>
- feat(behavior_velocity_planner): use XXXStamped in
autoware_internal_debug_msgs
(#9744)
- feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs
* fix
- fix(autoware_behavior_velocity_run_out_module): fix bugprone-branch-clone (#9715) fix: bugprone-error
- Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, kobayu858
0.40.0 (2024-12-12)
- Merge branch 'main' into release-0.40.0
- Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
- fix: fix ticket links in CHANGELOG.rst (#9588)
- chore(package.xml): bump version to 0.39.0
(#9587)
- chore(package.xml): bump version to 0.39.0
- fix: fix ticket links in CHANGELOG.rst
* fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>
- fix: fix ticket links in CHANGELOG.rst (#9588)
- fix(cpplint): include what you use - planning (#9570)
- feat(behavior_velocity_planner)!: remove stop_reason (#9452)
- 0.39.0
- update changelog
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- feat(behavior_velocity_planner): update velocity factor initialization for run out module (#9352) feat(behavior_velocity_planner): update velocity factor initialization Update the initialization of the velocity factor in the RunOutModule of the behavior_velocity_planner. The velocity factor is now initialized for the RUN_OUT behavior instead of the ROUTE_OBSTACLE behavior.
- fix(autoware_behavior_velocity_run_out_module): fix clang-diagnostic-unused-lambda-capture (#9416) fix: clang-diagnostic-unused-lambda-capture
- feat(run_out_module): add tests to run out
(#9222)
- WIP add tests for utils and path_utils
- add tests for utils and fix test path utils
- dynamic obstacles
- new tests and add function declarations
- add points for test of extractObstaclePointsWithinPolygon
- add state machine tests and other tests for dynamic obstacle
- remove unused test checks
- remove unused tests
- remove unwanted semicolons
- test
- add comments
* solve cpp-check limitation issue by removing namespaces ---------
- fix(run_out): output velocity factor
(#9319)
- fix(run_out): output velocity factor
* fix(adapi): subscribe run out velocity factor ---------
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- Contributors: Esteve Fernandez, Fumiya Watanabe, Kyoichi Sugahara, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo, danielsanchezaran, kobayu858
0.39.0 (2024-11-25)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- Contributors: Esteve Fernandez, Yutaka Kondo
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- refactor(object_recognition_utils): add autoware prefix to object_recognition_utils (#8946)
- fix(behavior_velocity_planner): align the parameters with launcher (#8791) parameters in behavior_velocity_planner aligned
- fix(autoware_behavior_velocity_run_out_module): fix unusedFunction (#8779) fix:unusedFunction
- fix(autoware_behavior_velocity_run_out_module): fix unusedFunction (#8669) fix:unusedFunction
- fix(behavior_velocity_planner): fix cppcheck warnings of virtualCallInConstructor (#8376) Co-authored-by: Ryuta Kambe <<ryuta.kambe@tier4.jp>>
- fix(behavior_velocity_planner): fix cppcheck warnings of functionStatic (#8262) fix: deal with functionStatic warnings
- fix(autoware_behavior_velocity_run_out_module): fix functionConst (#8284) fix:functionConst
- fix(autoware_behavior_velocity_run_out_module): fix
passedByValue
(#8215)
- fix:passedByValue
- fix:passedByValue
* fix:passedByValue ---------
- fix(autoware_behavior_velocity_run_out_module): fix constParameterReference (#8050) fix:constParameterReference
- fix(behavior_path_planner, behavior_velocity_planner): fix redefinition errors (#7688)
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- chore(behavior_velocity_planner): fix CODEOWNERS and page links
(#7534)
- chore(behavior_velocity_planner): fix CODEOWNERS and page links
* fix: fix page link ---------
- chore(behavior_velocity_planner): move packages (#7526)
- Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, Zhe Shen, kobayu858, taisa1
0.26.0 (2024-04-03)
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
eigen |
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_behavior_velocity_run_out_module at Robotics Stack Exchange
No questions yet, you can ask one here.
Failed to get question list, you can ticket an issue here