From 786e8af5f1b073d36603b60f8b010c2ed202d4d3 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 10 Aug 2023 11:05:41 +0900 Subject: [PATCH 1/3] feat(map_projection_loader): add map_projection_loader (#483) feat(map_loader): add map_projection_loader Signed-off-by: kminoda --- autoware_launch/config/map/lanelet2_map_loader.param.yaml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/autoware_launch/config/map/lanelet2_map_loader.param.yaml b/autoware_launch/config/map/lanelet2_map_loader.param.yaml index 9abbaf2901..24d2b0e8ed 100755 --- a/autoware_launch/config/map/lanelet2_map_loader.param.yaml +++ b/autoware_launch/config/map/lanelet2_map_loader.param.yaml @@ -1,7 +1,3 @@ /**: ros__parameters: - lanelet2_map_projector_type: MGRS # Options: MGRS, UTM, local - latitude: 40.81187906 # Latitude of map_origin, using in UTM - longitude: 29.35810110 # Longitude of map_origin, using in UTM - center_line_resolution: 5.0 # [m] From 1978d63d85a28f8d053b1ebfd4199804526a718d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 10 Aug 2023 12:05:06 +0900 Subject: [PATCH 2/3] feat(avoidance): make it selectable avoidance policy (#505) Signed-off-by: satoshi-ota --- .../avoidance/avoidance.param.yaml | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) 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 e751de2bb4..f27429ae81 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 @@ -175,10 +175,23 @@ max_distance: 20.0 # [m] stop_buffer: 1.0 # [m] - constraints: - # vehicle slows down under longitudinal constraints - use_constraints_for_decel: true # [-] + policy: + # policy for vehicle slow down behavior. select "best_effort" or "reliable". + # "best_effort": slow down deceleration & jerk are limited by constraints. + # but there is a possibility that the vehicle can't stop in front of the vehicle. + # "reliable": insert stop or slow down point with ignoring decel/jerk constraints. + # make it possible to increase chance to avoid but uncomfortable deceleration maybe happen. + deceleration: "best_effort" # [-] + # policy for avoidance lateral margin. select "best_effort" or "reliable". + # "best_effort": output avoidance path with shorten lateral margin when there is no enough longitudinal + # margin to avoid. + # "reliable": module output avoidance path with safe (rtc cooperate) state only when the vehicle can avoid + # with expected lateral margin. + lateral_margin: "best_effort" # [-] + # if true, module doesn't wait deceleration and outputs avoidance path by best effort margin. + use_shorten_margin_immediately: true # [-] + constraints: # lateral constraints lateral: velocity: [1.0, 1.38, 11.1] # [m/s] From 975fe46a7421bb03df7f4c39d6033289ea3a6ef0 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 12 Aug 2023 13:00:06 +0900 Subject: [PATCH 3/3] feat(autoware_launch): add polygon_generation_method in dynamic_avoidance (#508) Signed-off-by: Takayuki Murooka --- .../dynamic_avoidance/dynamic_avoidance.param.yaml | 2 ++ 1 file changed, 2 insertions(+) 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 377c0a8c21..fad859ac16 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,6 +42,8 @@ max_object_angle: 0.785 drivable_area_generation: + polygon_generation_method: "ego_path_base" # choose "ego_path_base" and "object_path_base" + lat_offset_from_obstacle: 0.8 # [m] max_lat_offset_to_avoid: 0.5 # [m] max_time_for_object_lat_shift: 0.0 # [s]