Skip to content

Commit 8a82fa9

Browse files
authoredJul 30, 2023
fix(start_planner): remove shift pull out enough distance check (#4422)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 86e0a01 commit 8a82fa9

File tree

2 files changed

+0
-31
lines changed

2 files changed

+0
-31
lines changed
 

‎planning/behavior_path_planner/include/behavior_path_planner/utils/start_planner/shift_pull_out.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -45,10 +45,6 @@ class ShiftPullOut : public PullOutPlannerBase
4545
const BehaviorPathPlannerParameters & common_parameter,
4646
const behavior_path_planner::StartPlannerParameters & parameter);
4747

48-
bool hasEnoughDistance(
49-
const double pull_out_total_distance, const lanelet::ConstLanelets & current_lanes,
50-
const Pose & current_pose, const bool isInGoalRouteSection, const Pose & goal_pose);
51-
5248
double calcBeforeShiftedArcLength(
5349
const PathWithLaneId & path, const double target_after_arc_length, const double dr);
5450

‎planning/behavior_path_planner/src/utils/start_planner/shift_pull_out.cpp

-27
Original file line numberDiff line numberDiff line change
@@ -216,14 +216,6 @@ std::vector<PullOutPath> ShiftPullOut::calcPullOutPaths(
216216
const double before_shifted_pull_out_distance =
217217
std::max(pull_out_distance, pull_out_distance_converted);
218218

219-
// check has enough distance
220-
const bool is_in_goal_route_section = route_handler.isInGoalRouteSection(road_lanes.back());
221-
if (!hasEnoughDistance(
222-
before_shifted_pull_out_distance, road_lanes, start_pose, is_in_goal_route_section,
223-
goal_pose)) {
224-
continue;
225-
}
226-
227219
// if before_shifted_pull_out_distance is too short, shifting path fails, so add non shifted
228220
if (before_shifted_pull_out_distance < RESAMPLE_INTERVAL && !has_non_shifted_path) {
229221
candidate_paths.push_back(non_shifted_path);
@@ -319,25 +311,6 @@ double ShiftPullOut::calcPullOutLongitudinalDistance(
319311
return min_pull_out_distance;
320312
}
321313

322-
bool ShiftPullOut::hasEnoughDistance(
323-
const double pull_out_total_distance, const lanelet::ConstLanelets & road_lanes,
324-
const Pose & current_pose, const bool is_in_goal_route_section, const Pose & goal_pose)
325-
{
326-
// the goal is far so current_lanes do not include goal's lane
327-
if (pull_out_total_distance > utils::getDistanceToEndOfLane(current_pose, road_lanes)) {
328-
return false;
329-
}
330-
331-
// current_lanes include goal's lane
332-
if (
333-
is_in_goal_route_section &&
334-
pull_out_total_distance > utils::getSignedDistance(current_pose, goal_pose, road_lanes)) {
335-
return false;
336-
}
337-
338-
return true;
339-
}
340-
341314
double ShiftPullOut::calcBeforeShiftedArcLength(
342315
const PathWithLaneId & path, const double target_after_arc_length, const double dr)
343316
{

0 commit comments

Comments
 (0)
Please sign in to comment.