@@ -643,12 +643,22 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence(
643
643
return lanelet_sequence;
644
644
}
645
645
646
- lanelet::ConstLanelets lanelet_sequence_forward =
647
- getLaneletSequenceAfter (lanelet, forward_distance, only_route_lanes);
646
+ const lanelet::ConstLanelets lanelet_sequence_forward = std::invoke ([&]() {
647
+ if (only_route_lanes) {
648
+ return getLaneletSequenceAfter (lanelet, forward_distance, only_route_lanes);
649
+ } else if (lanelet::utils::contains (shoulder_lanelets_, lanelet)) {
650
+ return getShoulderLaneletSequenceAfter (lanelet, forward_distance);
651
+ }
652
+ return lanelet::ConstLanelets{};
653
+ });
648
654
const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke ([&]() {
649
655
const auto arc_coordinate = lanelet::utils::getArcCoordinates ({lanelet}, current_pose);
650
656
if (arc_coordinate.length < backward_distance) {
651
- return getLaneletSequenceUpTo (lanelet, backward_distance, only_route_lanes);
657
+ if (only_route_lanes) {
658
+ return getLaneletSequenceUpTo (lanelet, backward_distance, only_route_lanes);
659
+ } else if (lanelet::utils::contains (shoulder_lanelets_, lanelet)) {
660
+ return getShoulderLaneletSequenceUpTo (lanelet, backward_distance);
661
+ }
652
662
}
653
663
return lanelet::ConstLanelets{};
654
664
});
0 commit comments