Skip to content

Commit

Permalink
fix(lane_change): fix terminal stop distance (#5392)
Browse files Browse the repository at this point in the history
* fix(lane_change): fix terminal stop distance

Signed-off-by: kosuke55 <[email protected]>

* make current lanes include path front id

Signed-off-by: kosuke55 <[email protected]>

* fixup! make current lanes include path front id

---------

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 authored Oct 25, 2023
1 parent 92f78a4 commit ce3db68
Showing 1 changed file with 17 additions and 2 deletions.
19 changes: 17 additions & 2 deletions planning/behavior_path_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3081,9 +3081,24 @@ lanelet::ConstLanelets getCurrentLanesFromPath(

lanelet::ConstLanelet current_lane;
lanelet::utils::query::getClosestLanelet(reference_lanes, current_pose, &current_lane);

return route_handler->getLaneletSequence(
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;
}

lanelet::ConstLanelets extendNextLane(
Expand Down

0 comments on commit ce3db68

Please sign in to comment.