From 580c18b99172ec2f9871fa915e59dc08466f11d3 Mon Sep 17 00:00:00 2001 From: mohammad alqudah Date: Wed, 27 Nov 2024 16:14:59 +0900 Subject: [PATCH] add delay lane change parameters Signed-off-by: mohammad alqudah --- .../lane_change/lane_change.param.yaml | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml index 3651222c0e..fe8915c784 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml @@ -6,10 +6,6 @@ backward_length_buffer_for_blocking_object: 3.0 # [m] backward_length_from_intersection: 5.0 # [m] - # side walk parked vehicle - object_check_min_road_shoulder_width: 0.5 # [m] - object_shiftable_ratio_threshold: 0.6 - # turn signal min_length_for_turn_signal_activation: 10.0 # [m] @@ -25,6 +21,13 @@ lon_acc_sampling_num: 5 lat_acc_sampling_num: 3 + # delay lane change + delay_lane_change: + enable: true + check_only_parked_vehicle: false + min_road_shoulder_width: 0.5 # [m] + th_parked_vehicle_shift_ratio: 0.6 + # safety check safety_check: allow_loose_check_for_cancel: true