Skip to content

Commit

Permalink
Revert "fix(lane_change): fix terminal stop distance (autowarefoundat…
Browse files Browse the repository at this point in the history
…ion#5392)"

This reverts commit 7da42ee.
  • Loading branch information
t4-x2 committed Oct 26, 2023
1 parent 12f5e64 commit b0bdcd0
Showing 1 changed file with 2 additions and 17 deletions.
19 changes: 2 additions & 17 deletions planning/behavior_path_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2994,24 +2994,9 @@ lanelet::ConstLanelets getCurrentLanesFromPath(

lanelet::ConstLanelet current_lane;
lanelet::utils::query::getClosestLanelet(reference_lanes, current_pose, &current_lane);
auto current_lanes = route_handler->getLaneletSequence(
current_lane, current_pose, p.backward_path_length, p.forward_path_length);

// Extend the 'current_lanes' with previous lanes until it contains 'front_lane_ids'.
const auto front_lane_ids = path.points.front().lane_ids;
auto have_front_lanes = [front_lane_ids](const auto & lanes) {
return std::any_of(lanes.begin(), lanes.end(), [&](const auto & lane) {
return std::find(front_lane_ids.begin(), front_lane_ids.end(), lane.id()) !=
front_lane_ids.end();
});
};
while (!have_front_lanes(current_lanes)) {
const auto extended_lanes = extendPrevLane(route_handler, current_lanes);
if (extended_lanes.size() == current_lanes.size()) break;
current_lanes = extended_lanes;
}

return current_lanes;
return route_handler->getLaneletSequence(
current_lane, current_pose, p.backward_path_length, p.forward_path_length);
}

lanelet::ConstLanelets extendNextLane(
Expand Down

0 comments on commit b0bdcd0

Please sign in to comment.