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-10 |
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
- Maxime Clement
- Mamoru Sobue
Authors
Dynamic Obstacle Stop
Role
dynamic_obstacle_stop
is a module that stops the ego vehicle from entering the immediate path of a dynamic object.
The immediate path of an object is the area that the object would traverse during a given time horizon, assuming constant velocity and heading.
Activation Timing
This module is activated if the launch parameter launch_dynamic_obstacle_stop_module
is set to true in the motion planning launch file.
Inner-workings / Algorithms
The module insert a stop point where the ego trajectory collides with the immediate path of an object. The overall module flow can be summarized with the following 4 steps.
- Filter dynamic objects.
- Calculate immediate path rectangles of the dynamic objects.
- Find earliest collision where ego collides with an immediate path rectangle.
- Insert stop point before the collision.
In addition to these 4 steps, 2 mechanisms are in place to make the stop point of this module more stable: an hysteresis and a decision duration buffer.
The hysteresis
parameter is used when a stop point was already being inserted in the previous iteration
and it increases the range where dynamic objects are considered close enough to the ego trajectory to be used by the module.
Filter dynamic objects
An object is considered by the module only if it meets all of the following conditions:
- it is a vehicle (pedestrians are ignored);
- it is moving at a velocity higher than defined by the
minimum_object_velocity
parameter; - it is not too close to the current position of the ego vehicle;
- it is not unavoidable (only if parameter
ignore_unavoidable_collisions
is set totrue
); - it is close to the ego trajectory.
An object is considered unavoidable if it is heading towards the ego vehicle such that even if ego stops, a collision would still occur (assuming the object keeps driving in a straight line).
For the last condition,
the object is considered close enough if its lateral distance from the ego trajectory is less than the threshold parameter minimum_object_distance_from_ego_trajectory
plus half the width of ego and of the object (including the extra_object_width
parameter).
In addition, the value of the hysteresis
parameter is added to the minimum distance if a stop point was inserted in the previous iteration.
Calculate immediate path rectangles
For each considered object, a rectangle is created representing its immediate path.
The rectangle has the width of the object plus the extra_object_width
parameter
and its length is the current speed of the object multiplied by the time_horizon
.
Find earliest collision
We build the ego trajectory footprints as the set of ego footprint polygons projected on each trajectory point. We then calculate the intersections between these ego trajectory footprints and the previously calculated immediate path rectangles. An intersection is ignored if the object is not driving toward ego, i.e., the absolute angle between the object and the trajectory point is larger than $\frac{3 \pi}{4}$.
The collision point with the lowest arc length when projected on the ego trajectory will be used to calculate the final stop point.
Insert stop point
Before inserting a stop point, we calculate the range of trajectory arc lengths where it can be inserted.
The minimum is calculated to satisfy the acceleration and jerk constraints of the vehicle.
If a stop point was inserted in the previous iteration of the module, its arc length is used as the maximum.
Finally,
the stop point arc length is calculated to be the arc length of the previously found collision point minus the stop_distance_buffer
and the ego vehicle longitudinal offset, clamped between the minimum and maximum values.
Duration buffer
To prevent chatter caused by noisy perception, two duration parameters are used.
-
add_stop_duration_buffer
represents the duration of consecutive collision detection with an object for the corresponding stop point to be added. -
remove_stop_duration_buffer
represents the duration of consecutive non-detection of collision with an object for the corresponding stop point to be removed.
Timers and collision points are tracked for each dynamic object independently.
Module Parameters
Parameter | Type | Description |
---|---|---|
extra_object_width |
double | [m] extra width around detected objects |
minimum_object_velocity |
double | [m/s] objects with a velocity bellow this value are ignored |
stop_distance_buffer |
double | [m] extra distance to add between the stop point and the collision point |
time_horizon |
double | [s] time horizon used for collision checks |
hysteresis |
double | [m] once a collision has been detected, this hysteresis is used on the collision detection |
add_stop_duration_buffer |
double | [s] duration where a collision must be continuously detected before a stop decision is added |
remove_stop_duration_buffer |
double | [s] duration between no collision being detected and the stop decision being remove |
minimum_object_distance_from_ego_trajectory |
double | [m] minimum distance between the footprints of ego and an object to consider for collision |
ignore_unavoidable_collisions |
bool | [-] if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight) |
Changelog for package autoware_motion_velocity_dynamic_obstacle_stop_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(dynamic_obstacle_stop): publish processing time when early return (#10254)
- Contributors: Hayato Mizushima, Maxime CLEMENT, 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)
- feat(motion_velocity_planner): common implementation for
motion_velocity_obstacle_<stop/slow_down/cruise>_module
(#10035)
- feat(motion_velocity_planner): prepare for motion_velocity_<stop/slow_down/cruise>_module
* update launch ---------
- Contributors: Fumiya Watanabe, Ryohsuke Mitsudome, Takayuki Murooka, 心刚
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
- feat(motion_velocity_planner)!: add _universe suffix to autoware_motion_velocity_planner_common and autoware_motion_velocity_planner_node (#9942)
- 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(motion_velocity_planner): introduce Object/Pointcloud
structure in PlannerData
(#9812)
- feat: new object/pointcloud struct in motion velocity planner
- update planner_data
- modify modules
* fix
- feat(motion_velocity_planner): remove unnecessary
tier4_planning_msgs dependency
(#9757)
- feat(motion_velocity_planner): remove unnecessary tier4_planning_msgs dependency
* fix
- feat(motion_velocity_planner): use Float64Stamped in autoware_internal_debug_msgs (#9745)
- Contributors: Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Takayuki Murooka
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)
- 0.39.0
- update changelog
- 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, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo
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
- test(dynamic_obstacle_stop): add tests and do some refactoring (#8250)
- fix(autoware_motion_velocity_dynamic_obstacle_stop_module): fix funcArgNamesDifferent (#8024) fix:funcArgNamesDifferent
- perf(dynamic_obstacle_stop): construct rtree nodes in place (#7753)
- perf(dynamic_obstacle_stop): create rtree with packing algorithm (#7730)
- feat(motion_velocity_planner, lane_departure_checker): add processing time Float64 publishers (#7683)
- feat(motion_velocity_planner): publish processing times (#7633)
- 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>>
- feat(motion_velocity_planner): rename include directories (#7523)
- refactor(dynamic_obstacle_stop): move to motion_velocity_planner (#7460)
- Contributors: Kosuke Takeuchi, Maxime CLEMENT, Takayuki Murooka, Yutaka Kondo, kobayu858
0.26.0 (2024-04-03)
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
libboost-dev |
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged autoware_motion_velocity_dynamic_obstacle_stop_module at Robotics Stack Exchange
No questions yet, you can ask one here.
Failed to get question list, you can ticket an issue here