Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]
Messages
Services
Plugins
Recent questions tagged obstacle_stop_planner at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.1.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-05-30 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Taiki Tanaka
- Tomoya Kimura
- Shumpei Wakabayashi
- Berkay Karaman
Authors
- Satoshi Ota
- Yukihiro Saito
Obstacle Stop Planner
Overview
obstacle_stop_planner
has following modules
- Obstacle Stop Planner
- inserts a stop point in trajectory when there is a static point cloud on the trajectory.
- Slow Down Planner
- inserts a deceleration section in trajectory when there is a point cloud near the trajectory.
- Adaptive Cruise Controller (ACC)
- embeds target velocity in trajectory when there is a dynamic point cloud on the trajectory.
Input topics
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::PointCloud2 | obstacle pointcloud |
~/input/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory |
~/input/vector_map |
autoware_auto_mapping_msgs::HADMapBin | vector map |
~/input/odometry |
nav_msgs::Odometry | vehicle velocity |
~/input/dynamic_objects |
autoware_auto_perception_msgs::PredictedObjects | dynamic objects |
~/input/expand_stop_range |
tier4_planning_msgs::msg::ExpandStopRange | expand stop range |
Output topics
Name | Type | Description |
---|---|---|
~output/trajectory |
autoware_auto_planning_msgs::Trajectory | trajectory to be followed |
~output/stop_reasons |
tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop |
Common Parameter
Parameter | Type | Description |
---|---|---|
enable_slow_down |
bool | enable slow down planner [-] |
max_velocity |
double | max velocity [m/s] |
chattering_threshold |
double | even if the obstacle disappears, the stop judgment continues for chattering_threshold [s] |
enable_z_axis_obstacle_filtering |
bool | filter obstacles in z axis (height) [-] |
z_axis_filtering_buffer |
double | additional buffer for z axis filtering [m] |
use_predicted_objects |
bool | whether to use predicted objects for collision and slowdown detection [-] |
predicted_object_filtering_threshold |
double | threshold for filtering predicted objects [valid only publish_obstacle_polygon true] [m] |
publish_obstacle_polygon |
bool | if use_predicted_objects is true, node publishes collision polygon [-] |
Obstacle Stop Planner
Role
This module inserts the stop point before the obstacle with margin. In nominal case, the margin is the sum
of baselink_to_front
and max_longitudinal_margin
. The baselink_to_front
means the distance between baselink
(
center of rear-wheel axis) and front of the car. The detection area is generated along the processed trajectory as
following figure. (This module cut off the input trajectory behind the ego position and decimates the trajectory points
for reducing computational costs.)
If another stop point has already been inserted by other modules within max_longitudinal_margin
, the margin is the sum
of baselink_to_front
and min_longitudinal_margin
. This feature exists to avoid stopping unnaturally position. (For
example, the ego stops unnaturally far away from stop line of crosswalk that pedestrians cross to without this feature.)
The module searches the obstacle pointcloud within detection area. When the pointcloud is
found, Adaptive Cruise Controller
modules starts to work. only when Adaptive Cruise Controller
modules does not
insert target velocity, the stop point is inserted to the trajectory. The stop point means the point with 0 velocity.
Restart prevention
If it needs X meters (e.g. 0.5 meters) to stop once the vehicle starts moving due to the poor vehicle control performance, the vehicle goes over the stopping position that should be strictly observed when the vehicle starts to moving in order to approach the near stop point (e.g. 0.3 meters away).
This module has parameter hold_stop_margin_distance
in order to prevent from these redundant restart. If the vehicle
is stopped within hold_stop_margin_distance
meters from stop point of the module, the module judges that the vehicle
has already stopped for the module’s stop point and plans to keep stopping current position even if the vehicle is
stopped due to other factors.
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/obstacle_stop_planner.launch.xml
-
- common_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/common.param.yaml]
- adaptive_cruise_control_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
- obstacle_stop_planner_param_path [default: $(find-pkg-share obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
- vehicle_info_param_file [default: $(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml]
- enable_slow_down [default: false]
- input_objects [default: /perception/object_recognition/objects]
- input_pointcloud [default: input/pointcloud]
- input_trajectory [default: input/trajectory]
- input_odometry [default: /localization/kinematic_state]
- output_trajectory [default: output/trajectory]
- output_velocity_limit [default: /planning/scenario_planning/max_velocity_candidates]
- output_velocity_limit_clear_command [default: /planning/scenario_planning/clear_velocity_limit]