From ccd004a3b514a9084cccc19b47a0819bdf6e3609 Mon Sep 17 00:00:00 2001 From: Shohei Sakai Date: Thu, 11 Apr 2024 08:42:35 +0900 Subject: [PATCH] feat: avoidance approval per maneuver v2.3.2 (#573) * avoidance approval per maneuver * tune lateral_execution_threshold to prevent sensitive behavior * update parameter name * Tune longitudinal distance from target --- .../avoidance/avoidance.param.yaml | 38 ++++++++++--------- 1 file changed, 21 insertions(+), 17 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 41ad4ebe14..8ee1f5a0ad 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 @@ -36,8 +36,8 @@ envelope_buffer_margin: 0.3 # [m] avoid_margin_lateral: 1.0 # [m] safety_buffer_lateral: 0.1 # [m] - safety_buffer_longitudinal: 0.0 # [m] - use_conservative_buffer_longitudinal: false # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. + safety_buffer_longitudinal: 5.0 # [m] + use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance. truck: is_target: true execute_num: 1 @@ -47,8 +47,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.4 - safety_buffer_longitudinal: 0.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true bus: is_target: true execute_num: 1 @@ -58,8 +58,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 - safety_buffer_longitudinal: 0.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true trailer: is_target: true execute_num: 1 @@ -69,8 +69,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 - safety_buffer_longitudinal: 0.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true unknown: is_target: false execute_num: 1 @@ -80,8 +80,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 1.0 safety_buffer_lateral: 0.7 - safety_buffer_longitudinal: 0.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true bicycle: is_target: true execute_num: 1 @@ -91,8 +91,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 - safety_buffer_longitudinal: 1.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true motorcycle: is_target: true execute_num: 1 @@ -102,8 +102,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 - safety_buffer_longitudinal: 1.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true pedestrian: is_target: true execute_num: 1 @@ -113,8 +113,8 @@ envelope_buffer_margin: 0.3 avoid_margin_lateral: 0.0 safety_buffer_lateral: 1.0 - safety_buffer_longitudinal: 1.0 - use_conservative_buffer_longitudinal: false + safety_buffer_longitudinal: 5.0 + use_conservative_buffer_longitudinal: true lower_distance_for_polygon_expansion: 30.0 # [m] upper_distance_for_polygon_expansion: 100.0 # [m] @@ -166,7 +166,7 @@ avoidance: # avoidance lateral parameters lateral: - lateral_execution_threshold: 0.09 # [m] + lateral_execution_threshold: 0.5 # [m] lateral_small_shift_threshold: 0.101 # [m] lateral_avoid_check_threshold: 0.1 # [m] soft_road_shoulder_margin: 0.3 # [m] @@ -193,6 +193,10 @@ stop_buffer: 1.0 # [m] policy: + # policy for rtc request. select "shift_line" or "maneuver". + # "shift_line": request approval for each shift line. + # "maneuver": request approval for avoidance maneuver (avoid + return). + approval: "maneuver" # policy for vehicle slow down behavior. select "best_effort" or "reliable". # "best_effort": slow down deceleration & jerk are limited by constraints. # but there is a possibility that the vehicle can't stop in front of the vehicle.