diff --git a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp index 9157079831ddc..5beaddcd9e279 100644 --- a/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/pull_out/pull_out_module.cpp @@ -176,7 +176,8 @@ BehaviorModuleOutput PullOutModule::plan() if (!status_.is_safe) { RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); - const PathWithLaneId stop_path = generateStopPath(); + // the path of getCurrent() is generated by generateStopPath() + const PathWithLaneId stop_path = getCurrentPath(); output.path = std::make_shared(stop_path); path_candidate_ = std::make_shared(stop_path); return output; @@ -285,11 +286,20 @@ BehaviorModuleOutput PullOutModule::planWaitingApproval() waitApproval(); BehaviorModuleOutput output; + if (!status_.is_safe) { + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, "Not found safe pull out path, publish stop path"); + // the path of getCurrent() is generated by generateStopPath() + const PathWithLaneId stop_path = getCurrentPath(); + output.path = std::make_shared(stop_path); + path_candidate_ = std::make_shared(stop_path); + return output; + } + const auto current_lanes = util::getExtendedCurrentLanes(planner_data_); const auto pull_out_lanes = pull_out_utils::getPullOutLanes(planner_data_); const auto drivable_lanes = util::generateDrivableLanesWithShoulderLanes(current_lanes, pull_out_lanes); - const auto expanded_lanes = util::expandLanelets( drivable_lanes, parameters_.drivable_area_left_bound_offset, parameters_.drivable_area_right_bound_offset); @@ -507,6 +517,7 @@ void PullOutModule::updatePullOutStatus() RCLCPP_WARN_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull out path, generate stop path"); status_.back_finished = true; // no need to drive backward + status_.pull_out_path.partial_paths.clear(); status_.pull_out_path.partial_paths.push_back(generateStopPath()); status_.pull_out_path.start_pose = current_pose; status_.pull_out_path.end_pose = current_pose;