From 1e17994a868910a64b41d0fccb569a0df85b1800 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Mon, 21 Oct 2024 20:22:29 +0900 Subject: [PATCH] feat(crosswalk_module): set the velocity of occluded objects to 2.0m/s (#1194) Signed-off-by: Maxime CLEMENT --- .../behavior_velocity_planner/crosswalk.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml index 3e99e140c8..5a0757401b 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/crosswalk.param.yaml @@ -80,7 +80,7 @@ # param for occlusions occlusion: enable: true # if true, ego will slowdown around crosswalks that are occluded - occluded_object_velocity: 1.0 # [m/s] assumed velocity of objects that may come out of the occluded space + occluded_object_velocity: 2.0 # [m/s] assumed velocity of objects that may come out of the occluded space slow_down_velocity: 1.0 # [m/s] time_buffer: 0.5 # [s] consecutive time with/without an occlusion to add/remove the slowdown min_size: 1.0 # [m] minimum size of an occlusion (square side size)