Go to the documentation of this file.
38 using Errors = std::vector<std::string>;
97 [[deprecated(
"Use laneletSubmap() to obtain a view on the elements within this route")]]
inline LaneletMapConstPtr
202 std::unique_ptr<internal::RouteGraph>
graph_;
ConstLanelets following(const ConstLanelet &lanelet) const
Similar to followingRelations but directly provides the following lanelets within the Route.
ConstLaneletOrAreas allConflictingInMap() const
Provides all lanelets in the map that conflict with any lanelet in the route.
ConstLanelets conflictingInRoute(const ConstLanelet &lanelet) const
Information about conflicting lanelets of a lanelet within the route.
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
void forEachSuccessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
ConstLanelets previous(const ConstLanelet &lanelet) const
Similar to followingRelations but directly provides the following lanelets within the Route.
std::shared_ptr< LaneletMap > LaneletMapPtr
LaneletRelations followingRelations(const ConstLanelet &lanelet) const
Provides information of the following lanelets within the Route.
LaneletRelations leftRelations(const ConstLanelet &lanelet) const
Provides information of the all lanelets left of a given lanelet within the Route.
LaneletRelations previousRelations(const ConstLanelet &lanelet) const
Provides information of the previous lanelets within the Route.
LaneletSubmapConstPtr laneletSubmap() const noexcept
A LaneletSubmap with all lanelets that are part of the route.
ConstLaneletOrAreas conflictingInMap(const ConstLanelet &lanelet) const
Information about conflicting lanelets of a lanelet within all passable lanelets in the laneletMap.
size_t numLanes() const
Returns the number of individual lanes.
LaneletSequence remainingLane(const ConstLanelet &ll) const
Returns that remaining lane a Lanelet belongs to.
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
void forEachPredecessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
Similar to forEachSuccessor but goes backwards in the routing graph instead of forwards.
const LaneletPath & shortestPath() const noexcept
Returns the shortest path that was the base of this route.
boost::optional< T > Optional
LaneletRelations rightRelations(const ConstLanelet &lanelet) const
Provides information of the all lanelets right of a given lanelet within the Route.
LaneletMapPtr getDebugLaneletMap() const
Get a laneletMap that represents the Lanelets of the Route and their relationship.
size_t size() const
Number of Lanelets in the route.
Optional< LaneletRelation > rightRelation(const ConstLanelet &lanelet) const
Provides information of the lanelet right of a given lanelet within the Route.
LaneletPath shortestPath_
The underlying shortest path used to create the route.
std::vector< LaneletRelation > LaneletRelations
Errors checkValidity(bool throwOnError=false) const
Perform some sanity checks on the route.
bool contains(const ConstLanelet &lanelet) const
Checks if a specific lanelet is part of the route.
std::vector< std::string > Errors
double length2d() const
Get the 2d length of the shortest path of this route.
Route & operator=(const Route &other)=delete
std::unique_ptr< internal::RouteGraph > graph_
The internal graph.
LaneletSubmapConstPtr laneletSubmap_
LaneletSubmap with all lanelets that are part of the route.
LaneletPath remainingShortestPath(const ConstLanelet &ll) const
Obtains the remaining shortest path to the destination. If the route is circular, the result will alw...
LaneletSequence fullLane(const ConstLanelet &ll) const
Returns the complete lane a Lanelet belongs to. Circular lanes will always have 'll' as the first ele...
std::function< bool(const LaneletVisitInformation &)> LaneletVisitFunction
The famous route object that marks a route from A to B.
Optional< LaneletRelation > leftRelation(const ConstLanelet &lanelet) const
Provides information of the lanelet left of a given lanelet within the Route.
std::shared_ptr< const LaneletSubmap > LaneletSubmapConstPtr
LaneletMapConstPtr laneletMap() const noexcept
A LaneletMap with all lanelets that are part of the route and those referenced by regelems.
std::vector< ConstLanelet > ConstLanelets
A lanelet path represents a set of lanelets that can be reached in order by either driving straight o...
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Thu Mar 6 2025 03:26:10