We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent c991bb8 commit 35f48daCopy full SHA for 35f48da
planning/route_handler/include/route_handler/route_handler.hpp
@@ -327,6 +327,7 @@ class RouteHandler
327
lanelet::ConstLanelets getShoulderLanelets() const;
328
bool isShoulderLanelet(const lanelet::ConstLanelet & lanelet) const;
329
bool isRouteLanelet(const lanelet::ConstLanelet & lanelet) const;
330
+ lanelet::ConstLanelets getPreferredLanelets() const;
331
332
// for path
333
PathWithLaneId getCenterLinePath(
planning/route_handler/src/route_handler.cpp
@@ -433,6 +433,11 @@ lanelet::ConstLanelets RouteHandler::getRouteLanelets() const
433
return route_lanelets_;
434
}
435
436
+lanelet::ConstLanelets RouteHandler::getPreferredLanelets() const
437
+{
438
+ return preferred_lanelets_;
439
+}
440
+
441
Pose RouteHandler::getStartPose() const
442
{
443
if (!route_ptr_) {
0 commit comments