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 2e59733ce3..94b36ca7fb 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 @@ -28,11 +28,11 @@ collision_start_margin_time: 2.0 collision_end_margin_time: 0.0 partially_prioritized: - collision_start_margin_time: 3.0 - collision_end_margin_time: 2.0 + collision_start_margin_time: 4.0 + collision_end_margin_time: 3.0 not_prioritized: - collision_start_margin_time: 3.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 2.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object + 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: 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 use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity @@ -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