From fdc69207bbe192604526b1ee13cde189970490b7 Mon Sep 17 00:00:00 2001 From: Berkay Karaman Date: Wed, 18 Sep 2024 21:49:18 +0300 Subject: [PATCH] fix(static_obstacle_avoidance): lower hard margin for parked car to handle dense urban scenarios https://github.com/autowarefoundation/autoware_launch/pull/1129 Signed-off-by: Ahmed Ebrahim Signed-off-by: beyza --- .../static_obstacle_avoidance.param.yaml | 30 +++++++++---------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml index 31e35dcad5..6dc57d3ce1 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/static_obstacle_avoidance.param.yaml @@ -23,9 +23,9 @@ th_moving_time: 2.0 # [s] longitudinal_margin: 0.0 # [m] lateral_margin: - soft_margin: 0.7 # [m] + soft_margin: 0.5 # [m] hard_margin: 0.2 # [m] - hard_margin_for_parked_vehicle: 0.7 # [m] + hard_margin_for_parked_vehicle: 0.2 # [m] max_expand_ratio: 0.0 # [-] FOR DEVELOPER envelope_buffer_margin: 0.1 # [m] FOR DEVELOPER th_error_eclipse_long_radius : 0.6 # [m] @@ -34,9 +34,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.7 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -45,9 +45,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.7 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -56,9 +56,9 @@ th_moving_time: 2.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.2 - hard_margin_for_parked_vehicle: 0.7 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.1 th_error_eclipse_long_radius : 0.6 @@ -67,7 +67,7 @@ th_moving_time: 1.0 longitudinal_margin: 0.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: -0.2 hard_margin_for_parked_vehicle: -0.2 max_expand_ratio: 0.0 @@ -80,7 +80,7 @@ lateral_margin: soft_margin: 0.7 hard_margin: 0.5 - hard_margin_for_parked_vehicle: 0.5 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 @@ -89,9 +89,9 @@ th_moving_time: 1.0 longitudinal_margin: 1.0 lateral_margin: - soft_margin: 0.7 + soft_margin: 0.5 hard_margin: 0.3 - hard_margin_for_parked_vehicle: 0.3 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 @@ -102,7 +102,7 @@ lateral_margin: soft_margin: 0.7 hard_margin: 0.5 - hard_margin_for_parked_vehicle: 0.5 + hard_margin_for_parked_vehicle: 0.2 max_expand_ratio: 0.0 envelope_buffer_margin: 0.5 th_error_eclipse_long_radius : 0.6 @@ -232,7 +232,7 @@ # avoidance distance parameters longitudinal: min_prepare_time: 1.0 # [s] - max_prepare_time: 3.0 # [s] + max_prepare_time: 2.0 # [s] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] FOR DEVELOPER @@ -294,7 +294,7 @@ velocity: [1.39, 4.17, 11.1] # [m/s] max_accel_values: [0.5, 0.5, 0.5] # [m/ss] min_jerk_values: [0.2, 0.2, 0.2] # [m/sss] - max_jerk_values: [1.0, 1.0, 1.0] # [m/sss] + max_jerk_values: [3.0, 3.0, 3.0] # [m/sss] # longitudinal constraints longitudinal: