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(start_planner): remove shift pull out enough distance check #4422

Merged
merged 1 commit into from
Jul 30, 2023
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 @@ -45,10 +45,6 @@ class ShiftPullOut : public PullOutPlannerBase
const BehaviorPathPlannerParameters & common_parameter,
const behavior_path_planner::StartPlannerParameters & parameter);

bool hasEnoughDistance(
const double pull_out_total_distance, const lanelet::ConstLanelets & current_lanes,
const Pose & current_pose, const bool isInGoalRouteSection, const Pose & goal_pose);

double calcBeforeShiftedArcLength(
const PathWithLaneId & path, const double target_after_arc_length, const double dr);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -216,14 +216,6 @@ std::vector<PullOutPath> ShiftPullOut::calcPullOutPaths(
const double before_shifted_pull_out_distance =
std::max(pull_out_distance, pull_out_distance_converted);

// check has enough distance
const bool is_in_goal_route_section = route_handler.isInGoalRouteSection(road_lanes.back());
if (!hasEnoughDistance(
before_shifted_pull_out_distance, road_lanes, start_pose, is_in_goal_route_section,
goal_pose)) {
continue;
}

// if before_shifted_pull_out_distance is too short, shifting path fails, so add non shifted
if (before_shifted_pull_out_distance < RESAMPLE_INTERVAL && !has_non_shifted_path) {
candidate_paths.push_back(non_shifted_path);
Expand Down Expand Up @@ -319,25 +311,6 @@ double ShiftPullOut::calcPullOutLongitudinalDistance(
return min_pull_out_distance;
}

bool ShiftPullOut::hasEnoughDistance(
const double pull_out_total_distance, const lanelet::ConstLanelets & road_lanes,
const Pose & current_pose, const bool is_in_goal_route_section, const Pose & goal_pose)
{
// the goal is far so current_lanes do not include goal's lane
if (pull_out_total_distance > utils::getDistanceToEndOfLane(current_pose, road_lanes)) {
return false;
}

// current_lanes include goal's lane
if (
is_in_goal_route_section &&
pull_out_total_distance > utils::getSignedDistance(current_pose, goal_pose, road_lanes)) {
return false;
}

return true;
}

double ShiftPullOut::calcBeforeShiftedArcLength(
const PathWithLaneId & path, const double target_after_arc_length, const double dr)
{
Expand Down