diff --git a/planning/route_handler/src/route_handler.cpp b/planning/route_handler/src/route_handler.cpp index fc9cb719f9af5..18a1710532e0c 100644 --- a/planning/route_handler/src/route_handler.cpp +++ b/planning/route_handler/src/route_handler.cpp @@ -449,6 +449,10 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceAfter( if (!getNextLaneletWithinRoute(current_lanelet, &next_lanelet)) { break; } + // loop check + if (lanelet.id() == next_lanelet.id()) { + break; + } lanelet_sequence_forward.push_back(next_lanelet); current_lanelet = next_lanelet; length += @@ -473,6 +477,12 @@ lanelet::ConstLanelets RouteHandler::getLaneletSequenceUpTo( if (!getPreviousLaneletsWithinRoute(current_lanelet, &candidate_lanelets)) { break; } + // loop check + if (std::any_of( + candidate_lanelets.begin(), candidate_lanelets.end(), + [lanelet](auto & prev_llt) { return lanelet.id() == prev_llt.id(); })) { + break; + } // If lanelet_sequence_backward with input lanelet contains all candidate lanelets, // break the loop.