From 4c03755a1aaa9cdb61ba5b6d168423dcda18bcd4 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Thu, 13 Jun 2024 17:04:08 +0900 Subject: [PATCH] refactor(dynamic_obstacle_stop): move to motion_velocity_planner (#1025) Signed-off-by: Maxime CLEMENT --- .../planning/preset/default_preset.yaml | 6 +-- .../dynamic_obstacle_stop.param.yaml | 2 +- .../tier4_planning_component.launch.xml | 2 +- autoware_launch/rviz/autoware.rviz | 48 +++++++++---------- 4 files changed, 29 insertions(+), 29 deletions(-) rename autoware_launch/config/planning/scenario_planning/lane_driving/{behavior_planning/behavior_velocity_planner => motion_planning/motion_velocity_planner}/dynamic_obstacle_stop.param.yaml (87%) diff --git a/autoware_launch/config/planning/preset/default_preset.yaml b/autoware_launch/config/planning/preset/default_preset.yaml index a8a9fac4f7..5a3139e4c5 100644 --- a/autoware_launch/config/planning/preset/default_preset.yaml +++ b/autoware_launch/config/planning/preset/default_preset.yaml @@ -77,9 +77,6 @@ launch: - arg: name: launch_no_drivable_lane_module default: "false" - - arg: - name: launch_dynamic_obstacle_stop_module - default: "true" # motion planning modules - arg: @@ -96,6 +93,9 @@ launch: # none # motion velocity planner modules + - arg: + name: launch_dynamic_obstacle_stop_module + default: "true" - arg: name: launch_out_of_lane_module default: "true" diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop.param.yaml similarity index 87% rename from autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml rename to autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop.param.yaml index ac95cd75c8..10d749e57a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/dynamic_obstacle_stop.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/dynamic_obstacle_stop.param.yaml @@ -8,5 +8,5 @@ hysteresis: 1.0 # [m] once a collision has been detected, this hysteresis is used on the collision detection add_stop_duration_buffer : 0.5 # [s] duration where a collision must be continuously detected before a stop decision is added remove_stop_duration_buffer : 1.0 # [s] duration between no collision being detected and the stop decision being remove - minimum_object_distance_from_ego_path: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision + minimum_object_distance_from_ego_trajectory: 1.0 # [m] minimum distance between the footprints of ego and an object to consider for collision ignore_unavoidable_collisions : true # if true, ignore collisions that cannot be avoided by stopping (assuming the obstacle continues going straight) diff --git a/autoware_launch/launch/components/tier4_planning_component.launch.xml b/autoware_launch/launch/components/tier4_planning_component.launch.xml index 60d0ae31df..1f929543d4 100644 --- a/autoware_launch/launch/components/tier4_planning_component.launch.xml +++ b/autoware_launch/launch/components/tier4_planning_component.launch.xml @@ -58,7 +58,6 @@ - @@ -74,6 +73,7 @@ +