From cb36d57e9a615b4fffe980e87a75fb75aa7e4144 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 1 Aug 2023 07:59:23 +0900 Subject: [PATCH 1/6] feat(avoidance): add parameter to configurate avoidance return point (#493) Signed-off-by: satoshi-ota --- .../behavior_path_planner/avoidance/avoidance.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml index edee0756e9..cff48985a2 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml @@ -160,6 +160,7 @@ # avoidance distance parameters longitudinal: prepare_time: 2.0 # [s] + remain_buffer_distance: 30.0 # [m] min_prepare_distance: 1.0 # [m] min_slow_down_speed: 1.38 # [m/s] buf_slow_down_speed: 0.56 # [m/s] From bd3f372a811d263eb61794fd0c01ccc15c94f9d9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 10:13:04 +0900 Subject: [PATCH 2/6] feat(autoware_launch): add acc/jerk parameters for stuck vehicle detection in crosswalk (#487) Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/crosswalk.param.yaml | 3 +++ 1 file changed, 3 insertions(+) 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 65ef41eff9..5fff846785 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 @@ -30,6 +30,9 @@ stuck_vehicle_velocity: 1.0 # [m/s] maximum velocity threshold whether the vehicle is stuck max_stuck_vehicle_lateral_offset: 2.0 # [m] maximum lateral offset for stuck vehicle position should be looked stuck_vehicle_attention_range: 10.0 # [m] the detection area is defined as X meters behind the crosswalk + min_acc: -1.0 # min acceleration [m/ss] + min_jerk: -1.0 # min jerk [m/sss] + max_jerk: 1.0 # max jerk [m/sss] # param for pass judge logic pass_judge: From 85db354c3106348a49efc53392db7b3efee63120 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 1 Aug 2023 10:37:55 +0900 Subject: [PATCH 3/6] feat(intersection_occlusion): ignore occlusion behind parked vehicles on the attention lane (#492) --- .../behavior_velocity_planner/intersection.param.yaml | 5 +++-- 1 file changed, 3 insertions(+), 2 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 e6bfc56a62..927a6bfaaf 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 @@ -2,7 +2,7 @@ ros__parameters: intersection: common: - attention_area_margin: 0.5 # [m] + attention_area_margin: 0.75 # [m] attention_area_length: 200.0 # [m] attention_area_angle_threshold: 0.785 # [rad] stop_line_margin: 3.0 @@ -46,7 +46,8 @@ min_vehicle_brake_for_rss: -2.5 # [m/s^2] max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph denoise_kernel: 1.0 # [m] - possible_object_bbox: [1.0, 2.0] # [m x m] + possible_object_bbox: [1.5, 2.5] # [m x m] + ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h enable_rtc: intersection: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval From 9a384c8b3e942967ab9a068b4d4634a88f4e17b6 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 1 Aug 2023 18:44:21 +0900 Subject: [PATCH 4/6] feat(autoware_launch): add option of disable_yield_for_new_stopped_object in crosswalk (#491) Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/crosswalk.param.yaml | 3 ++- 1 file changed, 2 insertions(+), 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 5fff846785..097b2c6c94 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 @@ -41,7 +41,8 @@ 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) ## param for yielding - disable_stop_for_yield_cancel: false + disable_stop_for_yield_cancel: false # for the crosswalk where there is a traffic signal + disable_yield_for_new_stopped_object: false # for the crosswalk where there is a traffic signal timeout_no_intention_to_walk: 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. timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not From b9f7c0e7082dc3dd1ed11904684cdbabd107b208 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 1 Aug 2023 22:12:56 +0900 Subject: [PATCH 5/6] feat(out_of_lane): add param for the min confidence of a predicted path (#440) Signed-off-by: Maxime CLEMENT Co-authored-by: Takayuki Murooka --- .../behavior_velocity_planner/out_of_lane.param.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml index c501599b4a..dd4c1c6102 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/out_of_lane.param.yaml @@ -16,6 +16,7 @@ minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored use_predicted_paths: true # if true, use the predicted paths to estimate future positions. # if false, assume the object moves at constant velocity along *all* lanelets it currently is located in. + predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value. overlap: minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered From 3cf58d2e75f01fc5a5dd18b7391c426922909c13 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Tue, 1 Aug 2023 22:59:34 +0900 Subject: [PATCH 6/6] refactor(traffic_light_arbiter): add traffic_light_arbiter param file (#489) Signed-off-by: Tomohito Ando Co-authored-by: Kenzo Lobos Tsunekawa --- .../traffic_light_arbiter/traffic_light_arbiter.param.yaml | 5 +++++ .../launch/components/tier4_perception_component.launch.xml | 3 +++ 2 files changed, 8 insertions(+) create mode 100644 autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml diff --git a/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml b/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml new file mode 100644 index 0000000000..5dc2b62eaa --- /dev/null +++ b/autoware_launch/config/perception/traffic_light_arbiter/traffic_light_arbiter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + external_time_tolerance: 5.0 + perception_time_tolerance: 1.0 + external_priority: false diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index 1707815707..0dbbee6065 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -82,5 +82,8 @@ + + +