From 740164dec75097149cde7e9f4ceb3cef1766e447 Mon Sep 17 00:00:00 2001 From: Arjun Jagdish Ram Date: Tue, 25 Feb 2025 13:35:22 +0900 Subject: [PATCH] feat(autoware_motion_velocity_obstacle_slow_down_module): params for obstacle stop and slow down modules (#1330) * fix Signed-off-by: Arjun Jagdish Ram * style(pre-commit): autofix * fix Signed-off-by: Arjun Jagdish Ram --------- Signed-off-by: Arjun Jagdish Ram Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../motion_velocity_planner/obstacle_slow_down.param.yaml | 8 ++++++++ .../motion_velocity_planner/obstacle_stop.param.yaml | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_slow_down.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_slow_down.param.yaml index f826e4ccd6..faa5cd8c50 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_slow_down.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_slow_down.param.yaml @@ -42,6 +42,14 @@ pedestrian: true pointcloud: false + pointcloud: + pointcloud_voxel_grid_x: 0.05 + pointcloud_voxel_grid_y: 0.05 + pointcloud_voxel_grid_z: 100000.0 + pointcloud_cluster_tolerance: 1.0 + pointcloud_min_cluster_size: 1 + pointcloud_max_cluster_size: 100000 + min_lat_margin: 0.0 # lateral margin between obstacle and trajectory band with ego's width to avoid the conflict with the obstacle_stop max_lat_margin: 1.1 # lateral margin between obstacle and trajectory band with ego's width lat_hysteresis_margin: 0.2 diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_stop.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_stop.param.yaml index 21dbf5f5bc..4203a94df4 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_stop.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/motion_velocity_planner/obstacle_stop.param.yaml @@ -54,6 +54,14 @@ bicycle: false pedestrian: false + pointcloud: + pointcloud_voxel_grid_x: 0.05 + pointcloud_voxel_grid_y: 0.05 + pointcloud_voxel_grid_z: 100000.0 + pointcloud_cluster_tolerance: 1.0 + pointcloud_min_cluster_size: 1 + pointcloud_max_cluster_size: 100000 + # hysteresis for velocity obstacle_velocity_threshold_to_stop : 3.0 # stop planning is executed to the obstacle whose velocity is less than this value [m/s] obstacle_velocity_threshold_from_stop : 3.5 # stop planning is executed to the obstacle whose velocity is less than this value [m/s]