From 321db8957cb06db842ac9a6677f7fa3573b44759 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Date: Wed, 30 Aug 2023 13:46:51 +0900 Subject: [PATCH 1/7] chore: add default args for TLR models (#538) Signed-off-by: Shunsuke Miura --- .../launch/components/tier4_perception_component.launch.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index 65b8ac20bd..cf5b2dd98c 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -93,5 +93,9 @@ + + + + From a46e5551ea17f7bfc752b5880ada95b2cfc8d1d9 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 30 Aug 2023 14:50:20 +0900 Subject: [PATCH 2/7] feat(autoware_launch): add no stop decision parameters in crosswalk (#537) Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/crosswalk.param.yaml | 8 +++++++- 1 file changed, 7 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 4b0a1ffc43..0c12624f3b 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 @@ -42,7 +42,13 @@ ego_pass_later_margin_x: [0.0] # [[s]] time to vehicle margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_margin_y: [10.0] # [[s]] time to collision margin vector for object pass first situation (the module judges that ego don't have to stop at TTV + MARGIN < TTC condition) ego_pass_later_additional_margin: 0.5 # [s] additional time margin for object pass first situation to suppress chattering - max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of the crosswalk. + + no_stop_decision: + max_offset_to_crosswalk_for_yield: 0.0 # [m] maximum offset from ego's front to crosswalk for yield. Positive value means in front of 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] + 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 From d0e57332c5e0cb0e978f84f76f9531798dce75e1 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 30 Aug 2023 15:39:01 +0900 Subject: [PATCH 3/7] feat(intersection): suppress intersection occlusion chattering (#533) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 1 + 1 file changed, 1 insertion(+) 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 4e77e0591f..e35215612a 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 @@ -48,6 +48,7 @@ denoise_kernel: 1.0 # [m] possible_object_bbox: [1.5, 2.5] # [m x m] ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h + stop_release_margin_time: 1.5 # [s] 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 c2201c21374f2c1fab0aa95d44943fb221f7bb91 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 30 Aug 2023 17:43:48 +0900 Subject: [PATCH 4/7] feat(intersection): strict definition of stuck vehicle detection area (#532) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_planner/intersection.param.yaml | 3 +-- 1 file changed, 1 insertion(+), 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 e35215612a..00df2e2ced 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 @@ -14,8 +14,7 @@ consider_wrong_direction_vehicle: false stuck_vehicle: use_stuck_stopline: true # stopline generated before the first conflicting area - stuck_vehicle_detect_dist: 3.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. - stuck_vehicle_ignore_dist: 10.0 # obstacle stop max distance(5.0m) + stuck vehicle size / 2 (0.0m-) + stuck_vehicle_detect_dist: 5.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h # enable_front_car_decel_prediction: false # By default this feature is disabled # assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning From ef98f76e5a433cf37d56444d41ab2a0c7ea88792 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Thu, 31 Aug 2023 01:04:30 +0900 Subject: [PATCH 5/7] feat(autoware_launch): remove polygon_generation_method from dynamic_avoidance (#539) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance/dynamic_avoidance.param.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml index fe30397683..a05bdda099 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/dynamic_avoidance/dynamic_avoidance.param.yaml @@ -42,7 +42,6 @@ max_object_angle: 0.785 drivable_area_generation: - polygon_generation_method: "object_path_base" # choose "ego_path_base" and "object_path_base" object_path_base: min_longitudinal_polygon_margin: 3.0 # [m] From 1e48981bb34aea3078eb6326a5ac54366f2653a7 Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Thu, 31 Aug 2023 09:31:35 +0900 Subject: [PATCH 6/7] chore(rviz_config): add debug marker group (#541) Signed-off-by: Takamasa Horibe --- autoware_launch/rviz/autoware.rviz | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/autoware_launch/rviz/autoware.rviz b/autoware_launch/rviz/autoware.rviz index 915a296d79..296d707b13 100644 --- a/autoware_launch/rviz/autoware.rviz +++ b/autoware_launch/rviz/autoware.rviz @@ -2418,6 +2418,34 @@ Visualization Manager: Value: false Enabled: true Name: Control + - Class: rviz_common/Group + Displays: + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Map + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Sensing + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Localization + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Perception + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Planning + - Class: rviz_common/Group + Displays: ~ + Enabled: true + Name: Control + Enabled: false + Name: Debug Enabled: true Global Options: Background Color: 10; 10; 10 From b98fb034254a1761bb24a85588fff1d446366b6e Mon Sep 17 00:00:00 2001 From: Tomoya Kimura Date: Thu, 31 Aug 2023 09:54:34 +0900 Subject: [PATCH 7/7] feat(autoware_launch): enable emergency handling when resource monitoring state becomes error (#542) Signed-off-by: tomoya.kimura --- .../system/system_error_monitor/system_error_monitor.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml index 71dc2ac600..251486dafd 100644 --- a/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml +++ b/autoware_launch/config/system/system_error_monitor/system_error_monitor.param.yaml @@ -37,7 +37,7 @@ /autoware/system/node_alive_monitoring: default /autoware/system/emergency_stop_operation: default /autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" } - /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" } + /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" } /autoware/vehicle/node_alive_monitoring: default