diff --git a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml index f3af759875250..83ccb6c3a8c65 100644 --- a/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml +++ b/launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/pull_over/pull_over.param.yaml @@ -12,7 +12,7 @@ min_acc: -0.5 enable_shift_parking: true enable_arc_forward_parking: true - enable_arc_backward_parking: false + enable_arc_backward_parking: true # goal research search_priority: "efficient_path" # "efficient_path" or "close_goal" enable_goal_research: true diff --git a/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml b/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml index 814b09b6ba8ec..2ca8f21d3c9b4 100644 --- a/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml +++ b/planning/behavior_path_planner/config/pull_over/pull_over.param.yaml @@ -12,7 +12,7 @@ min_acc: -0.5 enable_shift_parking: true enable_arc_forward_parking: true - enable_arc_backward_parking: false + enable_arc_backward_parking: true # goal research search_priority: "efficient_path" # "efficient_path" or "close_goal" enable_goal_research: true diff --git a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp index bc2a50e3ae4f9..3f1da72939671 100644 --- a/planning/behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/src/behavior_path_planner_node.cpp @@ -371,7 +371,7 @@ PullOverParameters BehaviorPathPlannerNode::getPullOverParam() p.min_acc = dp("min_acc", -0.5); p.enable_shift_parking = dp("enable_shift_parking", true); p.enable_arc_forward_parking = dp("enable_arc_forward_parking", true); - p.enable_arc_backward_parking = dp("enable_arc_backward_parking", false); + p.enable_arc_backward_parking = dp("enable_arc_backward_parking", true); // goal research p.search_priority = dp("search_priority", "efficient_path"); p.enable_goal_research = dp("enable_goal_research", true);