From ba4d2e15c2c2d83a07f8d10000df13c634c360cc Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 3 Mar 2023 09:52:29 +0900 Subject: [PATCH 1/2] fix(behavior_path_planner): change pull over maximum_deceleration (#229) Signed-off-by: kosuke55 --- .../behavior_path_planner/pull_over/pull_over.param.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index f09439edf7..e46429ebe1 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -9,7 +9,7 @@ pull_over_minimum_velocity: 1.38 margin_from_boundary: 0.5 decide_path_distance: 10.0 - maximum_deceleration: 1.0 + maximum_deceleration: 0.5 # goal research enable_goal_research: true search_priority: "efficient_path" # "efficient_path" or "close_goal" From 08dd5b51e7f1a7826e937040717165cc796e02dc Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 4 Mar 2023 01:25:34 +0900 Subject: [PATCH 2/2] feat(behavior_path_planner): pull over freespace parking (#221) * feat(behavior_path_planner): pull over freespace parking Signed-off-by: kosuke55 * fix typo Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../pull_over/pull_over.param.yaml | 31 +++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index e46429ebe1..31dde6c5cd 100644 --- a/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/autoware_launch/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -36,6 +36,37 @@ minimum_lateral_jerk: 0.5 deceleration_interval: 15.0 after_pull_over_straight_distance: 1.0 + # freespace parking + enable_freespace_parking: true + freespace_parking: + planning_algorithm: "astar" # options: astar, rrtstar + velocity: 1.0 + vehicle_shape_margin: 1.0 + time_limit: 3000.0 + minimum_turning_radius: 5.0 + maximum_turning_radius: 5.0 + turning_radius_size: 1 + # search configs + theta_size: 144 + angle_goal_range: 6.0 + curve_weight: 1.2 + reverse_weight: 1.0 + lateral_goal_range: 0.5 + longitudinal_goal_range: 2.0 + # costmap configs + obstacle_threshold: 30 + # -- A* search Configurations -- + astar: + only_behind_solutions: false + use_back: false + distance_heuristic_weight: 1.0 + # -- RRT* search Configurations -- + rrtstar: + enable_update: true + use_informed_sampling: true + max_planning_time: 150.0 + neighbor_radius: 8.0 + margin: 1.0 # parallel parking path enable_arc_forward_parking: true enable_arc_backward_parking: true