From 325dc3b68b8f3a28d39e597b6b4fcb09f769f64f Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 15 Jun 2023 10:19:03 +0900 Subject: [PATCH] feat(avoidance): additional buffer for perception noise (#373) feat(avoidance): additional offset for perception noise Signed-off-by: satoshi-ota --- .../avoidance/avoidance.param.yaml | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index 20160c465a..13210eb68a 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -28,45 +28,55 @@ # avoidance is performed for the object type with true target_object: car: - enable: true - envelope_buffer_margin: 0.3 - safety_buffer_lateral: 0.7 - safety_buffer_longitudinal: 0.0 + enable: true # [-] + max_expand_ratio: 0.0 # [-] + envelope_buffer_margin: 0.3 # [m] + safety_buffer_lateral: 0.7 # [m] + safety_buffer_longitudinal: 0.0 # [m] truck: enable: true + max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bus: enable: true + max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 trailer: enable: true + max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 unknown: enable: false + max_expand_ratio: 0.0 envelope_buffer_margin: 0.3 safety_buffer_lateral: 0.7 safety_buffer_longitudinal: 0.0 bicycle: enable: false + max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 motorcycle: enable: false + max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 pedestrian: enable: false + max_expand_ratio: 0.0 envelope_buffer_margin: 0.8 safety_buffer_lateral: 1.0 safety_buffer_longitudinal: 1.0 + lower_distance_for_polygon_expansion: 30.0 # [m] + upper_distance_for_polygon_expansion: 100.0 # [m] # For target object filtering target_filtering: