From e3d7e7075848523773fb089e999dfea8f28d3816 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Thu, 30 Nov 2023 09:15:46 +0900 Subject: [PATCH] feat(intersection): tune param for smooth passing Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml index aeb0424bc2..68f0d8ea59 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/intersection.param.yaml @@ -29,10 +29,10 @@ collision_end_margin_time: 0.0 partially_prioritized: collision_start_margin_time: 4.0 - collision_end_margin_time: 6.0 + collision_end_margin_time: 3.0 not_prioritized: collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object + collision_end_margin_time: 3.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object keep_detection_vel_thr: 1.5 # == 5.4km/h. keep detection if ego is ego.vel < keep_detection_vel_thr ignore_on_amber_traffic_light: object_expected_deceleration: 2.0 # [m/ss] @@ -42,7 +42,7 @@ occlusion_attention_area_length: 70.0 # [m] enable_creeping: false # flag to use the creep velocity when reaching occlusion limit stop line occlusion_creep_velocity: 0.8333 # the creep velocity to occlusion limit stop line - peeking_offset: 1.0 # [m] offset for peeking into detection area + peeking_offset: 0.5 # [m] offset for peeking into detection area free_space_max: 43 occupied_min: 58 do_dp: true