From d91c508a2dce751b158460995434b601d7e53c21 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Tue, 26 Nov 2024 19:02:40 +0200 Subject: [PATCH 1/2] fix(static_obstacle_avoidance): improve avoidance for parked NPCs (#1129) Signed-off-by: Ahmed Ebrahim Signed-off-by: beyza --- .../static_obstacle_avoidance.param.yaml | 36 +++++++++---------- 1 file changed, 18 insertions(+), 18 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..3480bb66e5 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 @@ -76,33 +76,33 @@ bicycle: th_moving_speed: 0.28 th_moving_time: 1.0 - longitudinal_margin: 1.0 + longitudinal_margin: 0.6 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 motorcycle: th_moving_speed: 1.0 th_moving_time: 1.0 - longitudinal_margin: 1.0 + longitudinal_margin: 0.6 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 pedestrian: th_moving_speed: 0.28 th_moving_time: 1.0 - longitudinal_margin: 1.0 + longitudinal_margin: 0.6 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: From e14b2c849950930475fc644b78e62630f2510cd7 Mon Sep 17 00:00:00 2001 From: beyzanurkaya <32412808+beyzanurkaya@users.noreply.github.com> Date: Tue, 26 Nov 2024 20:02:58 +0300 Subject: [PATCH 2/2] fix(dynamic_obstacle_avoidance): improve avoidance for moving NPCs (#1170) Signed-off-by: beyza --- .../dynamic_obstacle_avoidance.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml index aa1fdb3048..9bba8c52dc 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/dynamic_obstacle_avoidance.param.yaml @@ -56,10 +56,10 @@ object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] - lat_offset_from_obstacle: 1.0 # [m] - margin_distance_around_pedestrian: 2.0 # [m] + lat_offset_from_obstacle: 0.3 # [m] + margin_distance_around_pedestrian: 0.8 # [m] predicted_path: - end_time_to_consider: 2.0 # [s] + end_time_to_consider: 1.0 # [s] threshold_confidence: 0.0 # [] not probability max_lat_offset_to_avoid: 0.5 # [m] max_time_for_object_lat_shift: 0.0 # [s]