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

autoware_obstacle_stop_planner package from autoware_universe repo

autoware_adapi_specs autoware_agnocast_wrapper autoware_auto_common autoware_component_interface_specs_universe autoware_component_interface_tools autoware_component_interface_utils autoware_cuda_dependency_meta autoware_fake_test_node autoware_glog_component autoware_goal_distance_calculator autoware_grid_map_utils autoware_path_distance_calculator autoware_polar_grid autoware_time_utils autoware_traffic_light_recognition_marker_publisher autoware_traffic_light_utils autoware_universe_utils tier4_api_utils autoware_autonomous_emergency_braking autoware_collision_detector autoware_control_performance_analysis autoware_control_validator autoware_external_cmd_selector autoware_joy_controller autoware_lane_departure_checker autoware_mpc_lateral_controller autoware_obstacle_collision_checker autoware_operation_mode_transition_manager autoware_pid_longitudinal_controller autoware_predicted_path_checker autoware_pure_pursuit autoware_shift_decider autoware_smart_mpc_trajectory_follower autoware_trajectory_follower_base autoware_trajectory_follower_node autoware_vehicle_cmd_gate autoware_control_evaluator autoware_kinematic_evaluator autoware_localization_evaluator autoware_perception_online_evaluator autoware_planning_evaluator autoware_scenario_simulator_v2_adapter tier4_autoware_api_launch tier4_control_launch tier4_localization_launch tier4_map_launch tier4_perception_launch tier4_planning_launch tier4_sensing_launch tier4_simulator_launch tier4_system_launch tier4_vehicle_launch autoware_geo_pose_projector autoware_gyro_odometer autoware_ar_tag_based_localizer autoware_landmark_manager autoware_lidar_marker_localizer autoware_localization_error_monitor autoware_ndt_scan_matcher autoware_pose2twist autoware_pose_covariance_modifier autoware_pose_estimator_arbiter autoware_pose_initializer autoware_pose_instability_detector yabloc_common yabloc_image_processing yabloc_monitor yabloc_particle_filter yabloc_pose_initializer autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_tf_generator autoware_bytetrack autoware_cluster_merger autoware_compare_map_segmentation autoware_crosswalk_traffic_light_estimator autoware_detected_object_feature_remover autoware_detected_object_validation autoware_detection_by_tracker autoware_elevation_map_loader autoware_euclidean_cluster autoware_ground_segmentation autoware_image_projection_based_fusion autoware_lidar_apollo_instance_segmentation autoware_lidar_centerpoint autoware_lidar_transfusion autoware_map_based_prediction autoware_multi_object_tracker autoware_object_merger autoware_object_range_splitter autoware_object_velocity_splitter autoware_occupancy_grid_map_outlier_filter autoware_probabilistic_occupancy_grid_map autoware_radar_crossing_objects_noise_filter autoware_radar_fusion_to_detected_object autoware_radar_object_clustering autoware_radar_object_tracker autoware_radar_tracks_msgs_converter autoware_raindrop_cluster_filter autoware_shape_estimation autoware_simple_object_merger autoware_tensorrt_classifier autoware_tensorrt_common autoware_tensorrt_yolox autoware_tracking_object_merger autoware_traffic_light_arbiter autoware_traffic_light_category_merger autoware_traffic_light_classifier autoware_traffic_light_fine_detector autoware_traffic_light_map_based_detector autoware_traffic_light_multi_camera_fusion autoware_traffic_light_occlusion_predictor autoware_traffic_light_selector autoware_traffic_light_visualization perception_utils autoware_costmap_generator autoware_external_velocity_limit_selector autoware_freespace_planner autoware_freespace_planning_algorithms autoware_mission_planner_universe autoware_obstacle_cruise_planner autoware_obstacle_stop_planner autoware_path_optimizer autoware_path_smoother autoware_planning_validator autoware_remaining_distance_time_calculator autoware_rtc_interface autoware_scenario_selector autoware_surround_obstacle_checker autoware_behavior_path_avoidance_by_lane_change_module autoware_behavior_path_dynamic_obstacle_avoidance_module autoware_behavior_path_external_request_lane_change_module autoware_behavior_path_goal_planner_module autoware_behavior_path_lane_change_module autoware_behavior_path_planner autoware_behavior_path_planner_common autoware_behavior_path_sampling_planner_module autoware_behavior_path_side_shift_module autoware_behavior_path_start_planner_module autoware_behavior_path_static_obstacle_avoidance_module autoware_behavior_velocity_blind_spot_module autoware_behavior_velocity_crosswalk_module autoware_behavior_velocity_detection_area_module autoware_behavior_velocity_intersection_module autoware_behavior_velocity_no_drivable_lane_module autoware_behavior_velocity_no_stopping_area_module autoware_behavior_velocity_occlusion_spot_module autoware_behavior_velocity_rtc_interface autoware_behavior_velocity_run_out_module autoware_behavior_velocity_speed_bump_module autoware_behavior_velocity_template_module autoware_behavior_velocity_traffic_light_module autoware_behavior_velocity_virtual_traffic_light_module autoware_behavior_velocity_walkway_module autoware_motion_velocity_dynamic_obstacle_stop_module autoware_motion_velocity_obstacle_cruise_module autoware_motion_velocity_obstacle_slow_down_module autoware_motion_velocity_obstacle_velocity_limiter_module autoware_motion_velocity_out_of_lane_module autoware_bezier_sampler autoware_frenet_planner autoware_path_sampler autoware_sampler_common autoware_cuda_pointcloud_preprocessor autoware_cuda_utils autoware_image_diagnostics autoware_image_transport_decompressor autoware_imu_corrector autoware_pcl_extensions autoware_pointcloud_preprocessor autoware_radar_scan_to_pointcloud2 autoware_radar_static_pointcloud_filter autoware_radar_threshold_filter autoware_radar_tracks_noise_filter autoware_livox_tag_filter autoware_carla_interface autoware_dummy_perception_publisher autoware_fault_injection autoware_learning_based_vehicle_model autoware_simple_planning_simulator autoware_vehicle_door_simulator tier4_dummy_object_rviz_plugin autoware_bluetooth_monitor autoware_component_monitor autoware_component_state_monitor autoware_default_adapi autoware_adapi_adaptors autoware_adapi_visualizers autoware_automatic_pose_initializer autoware_diagnostic_graph_aggregator autoware_diagnostic_graph_utils autoware_dummy_diag_publisher autoware_dummy_infrastructure autoware_duplicated_node_checker autoware_hazard_status_converter autoware_mrm_comfortable_stop_operator autoware_mrm_emergency_stop_operator autoware_mrm_handler autoware_processing_time_checker autoware_system_diagnostic_monitor autoware_system_monitor autoware_topic_relay_controller autoware_topic_state_monitor autoware_velodyne_monitor reaction_analyzer autoware_accel_brake_map_calibrator autoware_external_cmd_converter autoware_raw_vehicle_cmd_converter autoware_steer_offset_estimator autoware_bag_time_manager_rviz_plugin autoware_mission_details_overlay_rviz_plugin autoware_overlay_rviz_plugin autoware_string_stamped_rviz_plugin autoware_perception_rviz_plugin tier4_adapi_rviz_plugin tier4_camera_view_rviz_plugin tier4_datetime_rviz_plugin tier4_localization_rviz_plugin tier4_planning_factor_rviz_plugin tier4_planning_rviz_plugin tier4_state_rviz_plugin tier4_system_rviz_plugin tier4_traffic_light_rviz_plugin tier4_vehicle_rviz_plugin

Package Summary

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

Repository Summary

Checkout URI https://github.com/autowarefoundation/autoware_universe.git
VCS Type git
VCS Version main
Last Updated 2025-04-03
Dev Status UNMAINTAINED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The autoware_obstacle_stop_planner package

Additional Links

No additional links.

Maintainers

  • Satoshi Ota
  • Taiki Tanaka
  • Tomoya Kimura
  • Shumpei Wakabayashi
  • Berkay Karaman
  • Beyza Nur Kaya

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_planning_msgs::Trajectory trajectory
~/input/vector_map autoware_map_msgs::msg::LaneletMapBin vector map
~/input/odometry nav_msgs::Odometry vehicle velocity
~/input/dynamic_objects autoware_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_planning_msgs::Trajectory trajectory to be followed

Common Parameter

{{ json_to_markdown(“planning/autoware_obstacle_stop_planner/schema/common.schema.json”) }}

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

![example](./docs/collision_parameters.svg){width=1000}
parameters for obstacle stop planner
![example](./docs/stop_target.svg){width=1000}
target for obstacle stop planner

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

![example](./docs/min_longitudinal_margin.svg){width=1000}
minimum longitudinal margin

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.

![example](./docs/restart_prevention.svg){width=1000}
parameters
![example](./docs/restart.svg){width=1000}
outside the hold_stop_margin_distance
![example](./docs/keep_stopping.svg){width=1000}
inside the hold_stop_margin_distance

Parameters

{{ json_to_markdown(“planning/autoware_obstacle_stop_planner/schema/obstacle_stop_planner.schema.json”) }}

Stop position

Parameter Type Description
max_longitudinal_margin double margin between obstacle and the ego’s front [m]
max_longitudinal_margin_behind_goal double margin between obstacle and the ego’s front when the stop point is behind the goal[m]
min_longitudinal_margin double if any obstacle exists within max_longitudinal_margin, this module set margin as the value of stop margin to min_longitudinal_margin [m]
hold_stop_margin_distance double parameter for restart prevention (See above section) [m]

Obstacle detection area

Parameter Type Description
lateral_margin double lateral margin from the vehicle footprint for collision obstacle detection area [m]
step_length double step length for pointcloud search range [m]
enable_stop_behind_goal_for_obstacle bool enabling extend trajectory after goal lane for obstacle detection

Flowchart

@startuml
title insertStopPoint
start


:callback trajectory;

:trim trajectory from self-pose;

:decimate trajectory;

:generate detection area;

if ( search obstacle pointcloud in detection area?) then (yes(find))
else (no(not find))
  stop
endif

if ( insert target velocity by adaptive cruise module?) then (yes)
  stop
else (no)
endif

:insert stop point;


stop
@enduml

Slow Down Planner

Role

This module inserts the slow down section before the obstacle with forward margin and backward margin. The forward margin is the sum of baselink_to_front and longitudinal_forward_margin, and the backward margin is the sum of baselink_to_front and longitudinal_backward_margin. The ego keeps slow down velocity in slow down section. The velocity is calculated the following equation.

$v_{target} = v_{min} + \frac{l_{ld} - l_{vw}/2}{l_{margin}} (v_{max} - v_{min} )$

  • $v_{target}$ : slow down target velocity [m/s]
  • $v_{min}$ : min_slow_down_velocity [m/s]
  • $v_{max}$ : max_slow_down_velocity [m/s]
  • $l_{ld}$ : lateral deviation between the obstacle and the ego footprint [m]
  • $l_{margin}$ : lateral_margin [m]
  • $l_{vw}$ : width of the ego footprint [m]

The above equation means that the smaller the lateral deviation of the pointcloud, the lower the velocity of the slow down section.

![example](./docs/slow_down_parameters.svg){width=1000}
parameters for slow down planner
![example](./docs/slow_down_target.svg){width=1000}
target for slow down planner

Parameters

{{ json_to_markdown(“planning/autoware_obstacle_stop_planner/schema/adaptive_cruise_control.schema.json”) }}

Slow down section

Parameter Type Description
longitudinal_forward_margin double margin between obstacle and the ego’s front [m]
longitudinal_backward_margin double margin between obstacle and the ego’s rear [m]

Obstacle detection area

Parameter Type Description
lateral_margin double lateral margin from the vehicle footprint for slow down obstacle detection area [m]

Slow down target velocity

Parameter Type Description
max_slow_down_velocity double max slow down velocity [m/s]
min_slow_down_velocity double min slow down velocity [m/s]

Flowchart

@startuml
title insertDecelerationPoint
start


:callback trajectory;

:trim trajectory from self-pose;

:decimate trajectory;

:generate detection area;

if ( search obstacle pointcloud in detection area?) then (yes(find))
else (no(not find))
  stop
endif

:insert deceleration point;


stop
@enduml

Adaptive Cruise Controller

Role

Adaptive Cruise Controller module embeds maximum velocity in trajectory when there is a dynamic point cloud on the trajectory. The value of maximum velocity depends on the own velocity, the velocity of the point cloud ( = velocity of the front car), and the distance to the point cloud (= distance to the front car).

Parameter Type Description
adaptive_cruise_control.use_object_to_estimate_vel bool use dynamic objects for estimating object velocity or not (valid only if osp.use_predicted_objects false)
adaptive_cruise_control.use_pcl_to_estimate_vel bool use raw pointclouds for estimating object velocity or not (valid only if osp.use_predicted_objects false)
adaptive_cruise_control.consider_obj_velocity bool consider forward vehicle velocity to calculate target velocity in adaptive cruise or not
adaptive_cruise_control.obstacle_velocity_thresh_to_start_acc double start adaptive cruise control when the velocity of the forward obstacle exceeds this value [m/s]
adaptive_cruise_control.obstacle_velocity_thresh_to_stop_acc double stop acc when the velocity of the forward obstacle falls below this value [m/s]
adaptive_cruise_control.emergency_stop_acceleration double supposed minimum acceleration (deceleration) in emergency stop [m/ss]
adaptive_cruise_control.emergency_stop_idling_time double supposed idling time to start emergency stop [s]
adaptive_cruise_control.min_dist_stop double minimum distance of emergency stop [m]
adaptive_cruise_control.obstacle_emergency_stop_acceleration double supposed minimum acceleration (deceleration) in emergency stop [m/ss]
adaptive_cruise_control.max_standard_acceleration double supposed maximum acceleration in active cruise control [m/ss]
adaptive_cruise_control.min_standard_acceleration double supposed minimum acceleration (deceleration) in active cruise control [m/ss]
adaptive_cruise_control.standard_idling_time double supposed idling time to react object in active cruise control [s]
adaptive_cruise_control.min_dist_standard double minimum distance in active cruise control [m]
adaptive_cruise_control.obstacle_min_standard_acceleration double supposed minimum acceleration of forward obstacle [m/ss]
adaptive_cruise_control.margin_rate_to_change_vel double rate of margin distance to insert target velocity [-]
adaptive_cruise_control.use_time_compensation_to_calc_distance bool use time-compensation to calculate distance to forward vehicle
adaptive_cruise_control.p_coefficient_positive double coefficient P in PID control (used when target dist -current_dist >=0) [-]
adaptive_cruise_control.p_coefficient_negative double coefficient P in PID control (used when target dist -current_dist <0) [-]
adaptive_cruise_control.d_coefficient_positive double coefficient D in PID control (used when delta_dist >=0) [-]
adaptive_cruise_control.d_coefficient_negative double coefficient D in PID control (used when delta_dist <0) [-]
adaptive_cruise_control.object_polygon_length_margin double The distance to extend the polygon length the object in pointcloud-object matching [m]
adaptive_cruise_control.object_polygon_width_margin double The distance to extend the polygon width the object in pointcloud-object matching [m]
adaptive_cruise_control.valid_estimated_vel_diff_time double Maximum time difference treated as continuous points in speed estimation using a point cloud [s]
adaptive_cruise_control.valid_vel_que_time double Time width of information used for speed estimation in speed estimation using a point cloud [s]
adaptive_cruise_control.valid_estimated_vel_max double Maximum value of valid speed estimation results in speed estimation using a point cloud [m/s]
adaptive_cruise_control.valid_estimated_vel_min double Minimum value of valid speed estimation results in speed estimation using a point cloud [m/s]
adaptive_cruise_control.thresh_vel_to_stop double Embed a stop line if the maximum speed calculated by ACC is lower than this speed [m/s]
adaptive_cruise_control.lowpass_gain_of_upper_velocity double Lowpass-gain of target velocity
adaptive_cruise_control.use_rough_velocity_estimation: bool Use rough estimated velocity if the velocity estimation is failed (valid only if osp.use_predicted_objects false)
adaptive_cruise_control.rough_velocity_rate double In the rough velocity estimation, the velocity of front car is estimated as self current velocity * this value

Flowchart

@startuml
title insertTargetVelocity()
start

:get target vehicle point (*1) in detection area ;

partition Estimate-Target-Velocity {

if (Is there a DynamicObject on the target vehicle point?) then (yes)
:use the DynamicObject velocity\nas a target vehicle point velocity (*2);
else (no)

  if (The target vehicle point is found in the previous step?) then (yes)
  else (no (estimation failed))
  stop
  endif

  :estimate the target vehicle point velocity \nby the travel distance from the previous step;

  if (The estimated velocity is valid?) then (yes)
  else (no (estimation failed))
  stop
  endif

  :use the estimated velocity\nas a target vehicle point velocity (*2);

endif
}

if (Is the target vehicle point velocity fast enough?) then (yes)
else (no)
  stop
endif

if (calculate distance to the pointcloud from self-position?) then (yes)
else (no)
  stop
endif

:calculate target velocity to be inserted in the trajectory;

if (the target velocity is fast enough?) then (yes)
else (no)
  stop
endif

:insert the target velocity;

stop
@enduml

(*1) The target vehicle point is calculated as a closest obstacle PointCloud from ego along the trajectory.

(*2) The sources of velocity estimation can be changed by the following ROS parameters.

  • adaptive_cruise_control.use_object_to_estimate_vel
  • adaptive_cruise_control.use_pcl_to_estimate_vel

This module works only when the target point is found in the detection area of the Obstacle stop planner module.

The first process of this module is to estimate the velocity of the target vehicle point. The velocity estimation uses the velocity information of dynamic objects or the travel distance of the target vehicle point from the previous step. The dynamic object information is primal, and the travel distance estimation is used as a backup in case of the perception failure. If the target vehicle point is contained in the bounding box of a dynamic object geometrically, the velocity of the dynamic object is used as the target point velocity. Otherwise, the target point velocity is calculated by the travel distance of the target point from the previous step; that is (current_position - previous_position) / dt. Note that this travel distance based estimation fails when the target point is detected in the first time (it mainly happens in the cut-in situation). To improve the stability of the estimation, the median of the calculation result for several steps is used.

If the calculated velocity is within the threshold range, it is used as the target point velocity.

Only when the estimation is succeeded and the estimated velocity exceeds the value of obstacle_stop_velocity_thresh_*, the distance to the pointcloud from self-position is calculated. For prevent chattering in the mode transition, obstacle_velocity_thresh_to_start_acc is used for the threshold to start adaptive cruise, and obstacle_velocity_thresh_to_stop_acc is used for the threshold to stop adaptive cruise. When the calculated distance value exceeds the emergency distance $d_{emergency}$ calculated by emergency_stop parameters, target velocity to insert is calculated.

The emergency distance $d_{emergency}$ is calculated as follows.

$d_{emergency} = d_{margin_{emergency}} + t_{idling_{emergency}} \cdot v_{ego} + (-\frac{v_{ego}^2}{2 \cdot a_{ego_ {emergency}}}) - (-\frac{v_{obj}^2}{2 \cdot a_{obj_{emergency}}})$

  • $d_{margin_{emergency}}$ is a minimum margin to the obstacle pointcloud. The value of $d_{margin_{emergency}}$ depends on the parameter min_dist_stop
  • $t_{idling_{emergency}}$ is a supposed idling time. The value of $t_{idling_{emergency}}$ depends on the parameter emergency_stop_idling_time
  • $v_{ego}$ is a current velocity of own vehicle
  • $a_{ego_{{emergency}}}$ is a minimum acceleration (maximum deceleration) of own vehicle. The value of $a{ego_{_ {emergency}}}$ depends on the parameter emergency_stop_acceleration
  • $v_{obj}$ is a current velocity of obstacle pointcloud.
  • $a_{obj_{{emergency}}}$ is a supposed minimum acceleration of obstacle pointcloud. The value of $a{obj_{_ {emergency}}}$ depends on the parameter obstacle_emergency_stop_acceleration
  • *Above $X_{_{emergency}}$ parameters are used only in emergency situation.

The target velocity is determined to keep the distance to the obstacle pointcloud from own vehicle at the standard distance $d_{standard}$ calculated as following. Therefore, if the distance to the obstacle pointcloud is longer than standard distance, The target velocity becomes higher than the current velocity, and vice versa. For keeping the distance, a PID controller is used.

$d_{standard} = d_{margin_{standard}} + t_{idling_{standard}} \cdot v_{ego} + (-\frac{v_{ego}^2}{2 \cdot a_{ego_ {standard}}}) - (-\frac{v_{obj}^2}{2 \cdot a_{obj_{standard}}})$

  • $d_{margin_{standard}}$ is a minimum margin to the obstacle pointcloud. The value of $d_{margin_{standard}}$ depends on the parameter min_dist_stop
  • $t_{idling_{standard}}$ is a supposed idling time. The value of $t_{idling_{standard}}$ depends on the parameter standard_stop_idling_time
  • $v_{ego}$ is a current velocity of own vehicle
  • $a_{ego_{{standard}}}$ is a minimum acceleration (maximum deceleration) of own vehicle. The value of $a{ego_{_ {standard}}}$ depends on the parameter min_standard_acceleration
  • $v_{obj}$ is a current velocity of obstacle pointcloud.
  • $a_{obj_{{standard}}}$ is a supposed minimum acceleration of obstacle pointcloud. The value of $a{obj_{_ {standard}}}$ depends on the parameter obstacle_min_standard_acceleration
  • *Above $X_{_{standard}}$ parameters are used only in non-emergency situation.

adaptive_cruise

If the target velocity exceeds the value of thresh_vel_to_stop, the target velocity is embedded in the trajectory.

Known Limits

  • It is strongly depends on velocity planning module whether or not it moves according to the target speed embedded by Adaptive Cruise Controller module. If the velocity planning module is updated, please take care of the vehicle’s behavior as much as possible and always be ready for overriding.

  • The velocity estimation algorithm in Adaptive Cruise Controller is depend on object tracking module. Please note that if the object-tracking fails or the tracking result is incorrect, it the possibility that the vehicle behaves dangerously.

  • It does not work for backward driving, but publishes the path of the input as it is. Please use obstacle_cruise_planner if you want to stop against an obstacle when backward driving.

CHANGELOG

Changelog for package autoware_obstacle_stop_planner

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!: replace VelocityLimit messages with autoware_internal_planning_msgs (#10273)
  • feat: adaption to ROS nodes guidelines about directory structure (#10268)
  • fix(planning): add missing exec_depend (#10134)
    • fix(planning): add missing exec_depend
    • fix find-pkg-share

    * fix find-pkg-share ---------

  • feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
  • Contributors: Hayato Mizushima, NorahXiong, Ryohsuke Mitsudome, Takagi, Isamu, 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(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, 心刚

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(autoware_obstacle_stop_planner)!: tier4_debug_msgs changed to autoware_internal_debug_msgs in autoware_obstacle_stop_planner (#9906) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files planning/autoware_obstacle_stop_planner
  • feat(autoware_planning_test_manager): remove dependency of VirtualTrafficLightState and ExpandStopRange (#9953)
    • feat(autoware_planning_test_manager): remove dependency of virtual traffic light

    * modify obstacle_stop test code ---------

  • 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 ---------

  • fix(obstacle_stop_planner): migrate planning factor (#9939)
    • fix(obstacle_stop_planner): migrate planning factor

    * fix(autoware_default_adapi): add coversion map ---------

  • Contributors: Fumiya Watanabe, Satoshi OTA, Takayuki Murooka, Vishal Chauhan

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)
  • fix(obstacle_stop_planner): remove stop reason (#9465)
  • 0.39.0
  • update changelog
  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • fix(autoware_obstacle_stop_planner): fix cppcheck warnings (#9388)
  • 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, Ryuta Kambe, Satoshi OTA, Yutaka Kondo

0.39.0 (2024-11-25)

0.38.0 (2024-11-08)

  • unify package.xml version to 0.37.0
  • refactor(signal_processing): prefix package and namespace with autoware (#8541)
  • chore(planning): consistent parameters with autoware_launch (#8915)
    • chore(planning): consistent parameters with autoware_launch
    • update

    * fix json schema ---------

  • fix(other_planning_packages): align the parameters with launcher (#8793)
    • parameters in planning/others aligned

    * update json ---------

  • fix(autoware_obstacle_stop_planner): register obstacle stop planner node with autoware scoping (#8512) Register node plugin with autoware scoping
  • fix(autoware_obstacle_stop_planner): fix unusedFunction (#8643) fix:unusedFunction
  • refactor(autoware_obstacle_stop_planner): rework parameters (#7795)
  • fix(autoware_obstacle_stop_planner): fix cppcheck warning of functionStatic (#8264)
    • fix: deal with functionStatic warnings

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

  • fix(autoware_obstacle_stop_planner): fix functionConst (#8282) fix:functionConst
  • fix(autoware_obstacle_stop_planner): fix passedByValue (#8189) fix:passedByValue
  • fix(autoware_obstacle_stop_planner): fix funcArgNamesDifferent (#8018)
    • fix:funcArgNamesDifferent

    * fix:funcArgNamesDifferent ---------

  • refactor(autoware_obstacle_stop_planner): prefix package and namespace with autoware (#7565)
    • refactor(autoware_obstacle_stop_planner): prefix package and namespace with autoware

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

  • Contributors: Esteve Fernandez, Mukunda Bharatheesha, Takayuki Murooka, Yutaka Kondo, Yuxin Wang, Zhe Shen, kobayu858, taisa1

0.26.0 (2024-04-03)

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

  • launch/obstacle_stop_planner.launch.xml
      • common_param_path [default: $(find-pkg-share autoware_obstacle_stop_planner)/config/common.param.yaml]
      • adaptive_cruise_control_param_path [default: $(find-pkg-share autoware_obstacle_stop_planner)/config/adaptive_cruise_control.param.yaml]
      • obstacle_stop_planner_param_path [default: $(find-pkg-share autoware_obstacle_stop_planner)/config/obstacle_stop_planner.param.yaml]
      • vehicle_info_param_file [default: $(find-pkg-share autoware_vehicle_info_utils)/config/vehicle_info.param.yaml]
      • 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

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_obstacle_stop_planner at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro foxy. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.
No version for distro kinetic. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.