Skip to content

Commit

Permalink
fix(route_handler): query shoulder lane in getLaneletSequence() if on…
Browse files Browse the repository at this point in the history
…ly_route_lanes is false and the arg is shoulder type (autowarefoundation#6567)

Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
  • Loading branch information
soblin authored and karishma1911 committed Jun 3, 2024
1 parent aa8e10a commit c479720
Showing 1 changed file with 13 additions and 3 deletions.
16 changes: 13 additions & 3 deletions planning/route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -643,12 +643,22 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence(
return lanelet_sequence;
}

lanelet::ConstLanelets lanelet_sequence_forward =
getLaneletSequenceAfter(lanelet, forward_distance, only_route_lanes);
const lanelet::ConstLanelets lanelet_sequence_forward = std::invoke([&]() {
if (only_route_lanes) {
return getLaneletSequenceAfter(lanelet, forward_distance, only_route_lanes);
} else if (lanelet::utils::contains(shoulder_lanelets_, lanelet)) {
return getShoulderLaneletSequenceAfter(lanelet, forward_distance);
}
return lanelet::ConstLanelets{};
});
const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() {
const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose);
if (arc_coordinate.length < backward_distance) {
return getLaneletSequenceUpTo(lanelet, backward_distance, only_route_lanes);
if (only_route_lanes) {
return getLaneletSequenceUpTo(lanelet, backward_distance, only_route_lanes);
} else if (lanelet::utils::contains(shoulder_lanelets_, lanelet)) {
return getShoulderLaneletSequenceUpTo(lanelet, backward_distance);
}
}
return lanelet::ConstLanelets{};
});
Expand Down

0 comments on commit c479720

Please sign in to comment.