@@ -216,14 +216,6 @@ std::vector<PullOutPath> ShiftPullOut::calcPullOutPaths(
216
216
const double before_shifted_pull_out_distance =
217
217
std::max (pull_out_distance, pull_out_distance_converted);
218
218
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
-
227
219
// if before_shifted_pull_out_distance is too short, shifting path fails, so add non shifted
228
220
if (before_shifted_pull_out_distance < RESAMPLE_INTERVAL && !has_non_shifted_path) {
229
221
candidate_paths.push_back (non_shifted_path);
@@ -319,25 +311,6 @@ double ShiftPullOut::calcPullOutLongitudinalDistance(
319
311
return min_pull_out_distance;
320
312
}
321
313
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
-
341
314
double ShiftPullOut::calcBeforeShiftedArcLength (
342
315
const PathWithLaneId & path, const double target_after_arc_length, const double dr)
343
316
{
0 commit comments