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): pull_over checks lane departure only for parking part #2673

Merged
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 @@ -167,17 +167,6 @@ boost::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
p.point.pose.position.z = goal_pose.position.z;
}

// check lane departure with road and shoulder lanes
const auto drivable_lanes =
util::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes);
const auto expanded_lanes = util::expandLanelets(
drivable_lanes, parameters_.drivable_area_left_bound_offset,
parameters_.drivable_area_right_bound_offset);
if (lane_departure_checker_.checkPathWillLeaveLane(
util::transformToLanelets(expanded_lanes), shifted_path.path)) {
return {};
}

// set lane_id and velocity to shifted_path
for (size_t i = path_shifter.getShiftLines().front().start_idx;
i < shifted_path.path.points.size() - 1; ++i) {
Expand Down Expand Up @@ -212,6 +201,17 @@ boost::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
pull_over_path.debug_poses.push_back(shift_end_pose_road_lane);
pull_over_path.debug_poses.push_back(actual_shift_end_pose);

// check if the parking path will leave lanes
const auto drivable_lanes =
util::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes);
const auto expanded_lanes = util::expandLanelets(
drivable_lanes, parameters_.drivable_area_left_bound_offset,
parameters_.drivable_area_right_bound_offset);
if (lane_departure_checker_.checkPathWillLeaveLane(
util::transformToLanelets(expanded_lanes), pull_over_path.getParkingPath())) {
return {};
}

return pull_over_path;
}

Expand Down