From 96857078e3de3b564f4a5c4900eda00fb13700b0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C5=81ukasz=20Chojnacki?= Date: Wed, 15 Feb 2023 15:05:25 +0100 Subject: [PATCH] fix(autoware_launch): add z_axis_filtering params for obstacle_stop_planner node (#150) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Ɓukasz Chojnacki --- .../obstacle_stop_planner/obstacle_stop_planner.param.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml index d707a73bc..6924435eb 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/motion_planning/obstacle_stop_planner/obstacle_stop_planner.param.yaml @@ -4,6 +4,8 @@ lowpass_gain: 0.9 # gain parameter for low pass filter [-] max_velocity: 20.0 # max velocity [m/s] enable_slow_down: False # whether to use slow down planner [-] + enable_z_axis_obstacle_filtering: True # filter obstacles in z axis (height) [-] + z_axis_filtering_buffer: 0.0 # additional buffer for z axis filtering [m] voxel_grid_x: 0.05 # voxel grid x parameter for filtering pointcloud [m] voxel_grid_y: 0.05 # voxel grid y parameter for filtering pointcloud [m] voxel_grid_z: 100000.0 # voxel grid z parameter for filtering pointcloud [m]