From 31d9460eba61a8f0261375663b635489d4f28be5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 12 Jul 2023 21:42:54 +0900 Subject: [PATCH 1/2] feat(autoware_launch): add disable_stop_for_yield_cancel in crosswalk Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/crosswalk.param.yaml | 1 + 1 file changed, 1 insertion(+) 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 2bbc5d31fc..725e2f35b6 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 @@ -21,6 +21,7 @@ stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk # param for pass judge logic + disable_stop_for_yield_cancel: false ego_pass_first_margin: 6.0 # [s] time margin for ego pass first situation (the module judges that ego don't have to stop at TTC + MARGIN < TTV condition) ego_pass_later_margin: 10.0 # [s] time margin for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) From 0caee6833d7d49d9789df4925d37db231726604e Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 13 Jul 2023 12:29:51 +0900 Subject: [PATCH 2/2] update Signed-off-by: Takayuki Murooka --- .../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 725e2f35b6..b20c83b5fd 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 @@ -27,7 +27,7 @@ stop_object_velocity_threshold: 0.28 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.28 m/s = 1.0 kmph) min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph) max_yield_timeout: 3.0 # [s] if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. - ego_yield_query_stop_duration: 0.1 # [s] the amount of time which ego should be stopping to query whether it yields or not + ego_yield_query_stop_duration: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not # param for input data tl_state_timeout: 3.0 # [s] timeout threshold for traffic light signal