Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(behavior_path_planner): fix pull out stop path (#2699) #252

Merged
merged 1 commit into from
Jan 20, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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<PathWithLaneId>(stop_path);
path_candidate_ = std::make_shared<PathWithLaneId>(stop_path);
return output;
Expand Down Expand Up @@ -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<PathWithLaneId>(stop_path);
path_candidate_ = std::make_shared<PathWithLaneId>(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);
Expand Down Expand Up @@ -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;
Expand Down