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(goal_planner): use departure_check_lane for path #9423

Merged
merged 1 commit into from
Nov 22, 2024
Merged
Show file tree
Hide file tree
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 @@ -55,7 +55,6 @@ std::optional<PullOverPath> GeometricPullOver::plan(
if (road_lanes.empty() || pull_over_lanes.empty()) {
return {};
}
const auto lanes = utils::combineLanelets(road_lanes, pull_over_lanes);

const auto & p = parallel_parking_parameters_;
const double max_steer_angle =
Expand All @@ -69,10 +68,12 @@ std::optional<PullOverPath> GeometricPullOver::plan(
return {};
}

const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet(
pull_over_lanes, *planner_data->route_handler, left_side_parking_);
const auto arc_path = planner_.getArcPath();

// check lane departure with road and shoulder lanes
if (lane_departure_checker_.checkPathWillLeaveLane(lanes, arc_path)) return {};
if (lane_departure_checker_.checkPathWillLeaveLane({departure_check_lane}, arc_path)) return {};

auto pull_over_path_opt = PullOverPath::create(
getPlannerType(), id, planner_.getPaths(), planner_.getStartPose(), modified_goal_pose,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -292,18 +292,12 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
return is_footprint_in_any_polygon(footprint);
});
});
const bool is_in_lanes = std::invoke([&]() -> bool {
const auto drivable_lanes =
utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes);
const auto & dp = planner_data->drivable_area_expansion_parameters;
const auto expanded_lanes = utils::expandLanelets(
drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
dp.drivable_area_types_to_skip);
const auto combined_drivable = utils::combineDrivableLanes(
expanded_lanes, previous_module_output.drivable_area_info.drivable_lanes);
return !lane_departure_checker_.checkPathWillLeaveLane(
utils::transformToLanelets(combined_drivable), pull_over_path.parking_path());
});

const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet(
pull_over_lanes, *planner_data->route_handler, left_side_parking_);
const bool is_in_lanes = !lane_departure_checker_.checkPathWillLeaveLane(
{departure_check_lane}, pull_over_path.parking_path());

if (!is_in_parking_lots && !is_in_lanes) {
return {};
}
Expand Down
Loading