Skip to content

Commit 164ab15

Browse files
authoredMar 8, 2024
Merge pull request #1182 from tier4/cherry-pick/pr6567
fix(route_handler): query shoulder lane in getLaneletSequence() if only_route_lanes is false and the arg is shoulder type (autowarefoundation#6567)
2 parents bb387e8 + 0c4771e commit 164ab15

File tree

1 file changed

+13
-3
lines changed

1 file changed

+13
-3
lines changed
 

‎planning/route_handler/src/route_handler.cpp

+13-3
Original file line numberDiff line numberDiff line change
@@ -643,12 +643,22 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequence(
643643
return lanelet_sequence;
644644
}
645645

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+
});
648654
const lanelet::ConstLanelets lanelet_sequence_backward = std::invoke([&]() {
649655
const auto arc_coordinate = lanelet::utils::getArcCoordinates({lanelet}, current_pose);
650656
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+
}
652662
}
653663
return lanelet::ConstLanelets{};
654664
});

0 commit comments

Comments
 (0)