From 3fa16a194159cfca6664b293d4e6bb73a86b6c7a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Tue, 3 Oct 2023 06:57:28 +0900 Subject: [PATCH 1/3] feat(localization_error_monitor): update parameter (#614) Signed-off-by: kminoda --- .../config/localization/localization_error_monitor.param.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autoware_launch/config/localization/localization_error_monitor.param.yaml b/autoware_launch/config/localization/localization_error_monitor.param.yaml index 2aa28014ea..def5c80164 100644 --- a/autoware_launch/config/localization/localization_error_monitor.param.yaml +++ b/autoware_launch/config/localization/localization_error_monitor.param.yaml @@ -1,7 +1,7 @@ /**: ros__parameters: scale: 3.0 - error_ellipse_size: 1.0 - warn_ellipse_size: 0.8 + error_ellipse_size: 1.5 + warn_ellipse_size: 1.2 error_ellipse_size_lateral_direction: 0.3 warn_ellipse_size_lateral_direction: 0.25 From dee409f7716b324a29e43dc9a3bf6f14fa5968af Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Tue, 3 Oct 2023 10:55:17 +0900 Subject: [PATCH 2/3] fix(autoware_launch): improve stop decision in out_of_lane (#615) Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/out_of_lane.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/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 510dc86ef6..c74c5b3d87 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 @@ -24,8 +24,7 @@ action: # action to insert in the path if an object causes a conflict at an overlap skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed - strict: true # if true, when a decision is taken to avoid entering a lane, the stop point will make sure no lane at all is entered by ego - # if false, ego stops just before entering a lane but may then be overlapping another lane. + precision: 0.1 # [m] precision when inserting a stop pose in the path distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane slowdown: distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap From b951b5190232b3bd36b982a355dbbe6041e0b0f3 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 3 Oct 2023 12:11:39 +0900 Subject: [PATCH 3/3] feat(autoware_launch): dynamic timeout for no intention to walk decision in crosswalk (#610) * feat(autoware_launch): dynamic timeout for no intention to walk decision in crosswalk Signed-off-by: Takayuki Murooka * update config Signed-off-by: Takayuki Murooka * revert a parg of config Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../behavior_velocity_planner/crosswalk.param.yaml | 4 +++- 1 file changed, 3 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 0c12624f3b..4b81a1e687 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 @@ -54,7 +54,9 @@ ## param for yielding 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. + # if the pedestrian does not move for X seconds after stopping before the crosswalk, the module judge that ego is able to pass first. + distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order + timeout_map_for_no_intention_to_walk: [3.0, 0.0] # [s] timeout_ego_stop_for_yield: 3.0 # [s] the amount of time which ego should be stopping to query whether it yields or not # param for target object filtering