Public Types | Public Member Functions | Private Attributes | List of all members
lanelet::routing::Route Class Reference

The famous route object that marks a route from A to B. More...

#include <Route.h>

Public Types

using Errors = std::vector< std::string >
 

Public Member Functions

ConstLaneletOrAreas allConflictingInMap () const
 Provides all lanelets in the map that conflict with any lanelet in the route. More...
 
Errors checkValidity (bool throwOnError=false) const
 Perform some sanity checks on the route. More...
 
ConstLaneletOrAreas conflictingInMap (const ConstLanelet &lanelet) const
 Information about conflicting lanelets of a lanelet within all passable lanelets in the laneletMap. More...
 
ConstLanelets conflictingInRoute (const ConstLanelet &lanelet) const
 Information about conflicting lanelets of a lanelet within the route. More...
 
bool contains (const ConstLanelet &lanelet) const
 Checks if a specific lanelet is part of the route. More...
 
ConstLanelets following (const ConstLanelet &lanelet) const
 Similar to followingRelations but directly provides the following lanelets within the Route. More...
 
LaneletRelations followingRelations (const ConstLanelet &lanelet) const
 Provides information of the following lanelets within the Route. More...
 
void forEachPredecessor (const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
 Similar to forEachSuccessor but goes backwards in the routing graph instead of forwards. More...
 
void forEachSuccessor (const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
 
LaneletSequence fullLane (const ConstLanelet &ll) const
 Returns the complete lane a Lanelet belongs to. Circular lanes will always have 'll' as the first element. More...
 
LaneletMapPtr getDebugLaneletMap () const
 Get a laneletMap that represents the Lanelets of the Route and their relationship. More...
 
LaneletMapConstPtr laneletMap () const noexcept
 A LaneletMap with all lanelets that are part of the route and those referenced by regelems. More...
 
LaneletSubmapConstPtr laneletSubmap () const noexcept
 A LaneletSubmap with all lanelets that are part of the route. More...
 
Optional< LaneletRelationleftRelation (const ConstLanelet &lanelet) const
 Provides information of the lanelet left of a given lanelet within the Route. More...
 
LaneletRelations leftRelations (const ConstLanelet &lanelet) const
 Provides information of the all lanelets left of a given lanelet within the Route. More...
 
double length2d () const
 Get the 2d length of the shortest path of this route. More...
 
size_t numLanes () const
 Returns the number of individual lanes. More...
 
Routeoperator= (const Route &other)=delete
 
Routeoperator= (Route &&other) noexcept
 
ConstLanelets previous (const ConstLanelet &lanelet) const
 Similar to followingRelations but directly provides the following lanelets within the Route. More...
 
LaneletRelations previousRelations (const ConstLanelet &lanelet) const
 Provides information of the previous lanelets within the Route. More...
 
LaneletSequence remainingLane (const ConstLanelet &ll) const
 Returns that remaining lane a Lanelet belongs to. More...
 
LaneletPath remainingShortestPath (const ConstLanelet &ll) const
 Obtains the remaining shortest path to the destination. If the route is circular, the result will always have the same length and end before the lanelet passed as input argument. More...
 
Optional< LaneletRelationrightRelation (const ConstLanelet &lanelet) const
 Provides information of the lanelet right of a given lanelet within the Route. More...
 
LaneletRelations rightRelations (const ConstLanelet &lanelet) const
 Provides information of the all lanelets right of a given lanelet within the Route. More...
 
 Route ()
 
 Route (const Route &other)=delete
 
 Route (LaneletPath shortestPath, std::unique_ptr< internal::RouteGraph > graph, LaneletSubmapConstPtr laneletSubmap) noexcept
 Constructs a route. Not supposed to be called directly. Use RoutingGraph to obtain routes. More...
 
 Route (Route &&other) noexcept
 
const LaneletPathshortestPath () const noexcept
 Returns the shortest path that was the base of this route. More...
 
size_t size () const
 Number of Lanelets in the route. More...
 
 ~Route () noexcept
 

Private Attributes

std::unique_ptr< internal::RouteGraphgraph_
 The internal graph. More...
 
LaneletSubmapConstPtr laneletSubmap_
 LaneletSubmap with all lanelets that are part of the route. More...
 
LaneletPath shortestPath_
 The underlying shortest path used to create the route. More...
 

Detailed Description

The famous route object that marks a route from A to B.

Definition at line 36 of file Route.h.

Member Typedef Documentation

◆ Errors

using lanelet::routing::Route::Errors = std::vector<std::string>

Definition at line 38 of file Route.h.

Constructor & Destructor Documentation

◆ Route() [1/4]

lanelet::routing::Route::Route ( )
default

◆ Route() [2/4]

lanelet::routing::Route::Route ( const Route other)
delete

◆ Route() [3/4]

lanelet::routing::Route::Route ( Route &&  other)
defaultnoexcept

◆ ~Route()

lanelet::routing::Route::~Route ( )
defaultnoexcept

◆ Route() [4/4]

lanelet::routing::Route::Route ( LaneletPath  shortestPath,
std::unique_ptr< internal::RouteGraph graph,
LaneletSubmapConstPtr  laneletSubmap 
)
noexcept

Constructs a route. Not supposed to be called directly. Use RoutingGraph to obtain routes.

Member Function Documentation

◆ allConflictingInMap()

ConstLaneletOrAreas lanelet::routing::Route::allConflictingInMap ( ) const

Provides all lanelets in the map that conflict with any lanelet in the route.

Definition at line 344 of file Route.cpp.

◆ checkValidity()

Route::Errors lanelet::routing::Route::checkValidity ( bool  throwOnError = false) const

Perform some sanity checks on the route.

Parameters
throwOnErrorThrow or not-throw an exception if errors are found
Exceptions
Throwsif errors are encountered and throwOnError is true
Returns
Vector of errors if no-throw is chosen and errors are found

Definition at line 363 of file Route.cpp.

◆ conflictingInMap()

ConstLaneletOrAreas lanelet::routing::Route::conflictingInMap ( const ConstLanelet lanelet) const

Information about conflicting lanelets of a lanelet within all passable lanelets in the laneletMap.

Parameters
laneletLanelet to find conflicting lanelets to
Returns
Vector of conflicting lanelets. Empty vector if input lanelet is not part of the route. Lanelets that are also conflicting in route are returned as well.
See also
conflictingInRoute

Definition at line 336 of file Route.cpp.

◆ conflictingInRoute()

ConstLanelets lanelet::routing::Route::conflictingInRoute ( const ConstLanelet lanelet) const

Information about conflicting lanelets of a lanelet within the route.

Parameters
laneletLanelet to find conflicting lanelets to
Returns
Vector of conflicting lanelets. Empty vector if input lanelet is not part of the route.
See also
conflictingInMap

Definition at line 328 of file Route.cpp.

◆ contains()

bool lanelet::routing::Route::contains ( const ConstLanelet lanelet) const

Checks if a specific lanelet is part of the route.

Definition at line 352 of file Route.cpp.

◆ following()

ConstLanelets lanelet::routing::Route::following ( const ConstLanelet lanelet) const

Similar to followingRelations but directly provides the following lanelets within the Route.

Definition at line 235 of file Route.cpp.

◆ followingRelations()

LaneletRelations lanelet::routing::Route::followingRelations ( const ConstLanelet lanelet) const

Provides information of the following lanelets within the Route.

Parameters
laneletLanelet to get information about.
Returns
Relations to following lanelets in the route. Nothing if 'lanelet' is not part of the route. The relation will always be "succesor"

Definition at line 227 of file Route.cpp.

◆ forEachPredecessor()

void lanelet::routing::Route::forEachPredecessor ( const ConstLanelet lanelet,
const LaneletVisitFunction f 
) const

Similar to forEachSuccessor but goes backwards in the routing graph instead of forwards.

Definition at line 314 of file Route.cpp.

◆ forEachSuccessor()

void lanelet::routing::Route::forEachSuccessor ( const ConstLanelet lanelet,
const LaneletVisitFunction f 
) const

Can be used to search the route object with a custom function that is called for the successors of lanelet. This function works similar to RoutingGraph::forEachSuccessor. Which costs and whether lane changes are used to determine the shortest path depends on the cost id that was used to create this route object.

Definition at line 301 of file Route.cpp.

◆ fullLane()

LaneletSequence lanelet::routing::Route::fullLane ( const ConstLanelet ll) const

Returns the complete lane a Lanelet belongs to. Circular lanes will always have 'll' as the first element.

Parameters
llLanelet to get lane for
Returns
All lanelets of that route. Nothing if Lanelet is not part of the route.

If

Definition at line 154 of file Route.cpp.

◆ getDebugLaneletMap()

LaneletMapPtr lanelet::routing::Route::getDebugLaneletMap ( ) const

Get a laneletMap that represents the Lanelets of the Route and their relationship.

Returns
The laneletMap Note that this laneletMap won't contain any Lanelets but rather just points and line string that represent the lanelets and their relationship.

Definition at line 202 of file Route.cpp.

◆ laneletMap()

LaneletMapConstPtr lanelet::routing::Route::laneletMap ( ) const
inlinenoexcept

A LaneletMap with all lanelets that are part of the route and those referenced by regelems.

Returns
A laneletMap with all lanelets of the route, excluding regulatory elements. Can be used to do spatial lookups like 'which Lanelets of the route are close to my position'. Note that not all lanelets in the map automatically belong to the route. They can also belong to one of the regulatory elements of the lanelet. Use Route::contains for that.

Due to this behaviour that the map can contain lanelets that are not on the route, this function is deprecated. laneletSubmap() only returns lanelets on the map. To get the old behaviour use laneletSubmap()->laneletMap().

Definition at line 98 of file Route.h.

◆ laneletSubmap()

LaneletSubmapConstPtr lanelet::routing::Route::laneletSubmap ( ) const
inlinenoexcept

A LaneletSubmap with all lanelets that are part of the route.

Can be used to do spatial lookups like 'which Lanelets of the route are close to my position'. It does not contain anything beyond that, no points, linestrings, etc.

Definition at line 86 of file Route.h.

◆ leftRelation()

Optional< LaneletRelation > lanelet::routing::Route::leftRelation ( const ConstLanelet lanelet) const

Provides information of the lanelet left of a given lanelet within the Route.

Note
The returned lanelet can include a lanelet that can be switched or not-switched to. The relation will be "left" and "adjacent_left" accordingly.
Parameters
laneletLanelet to get information about.
Returns
Relation to lanelet left of the input lanelet in the route. Nothing if 'lanelet' is not part of the route.

Definition at line 259 of file Route.cpp.

◆ leftRelations()

LaneletRelations lanelet::routing::Route::leftRelations ( const ConstLanelet lanelet) const

Provides information of the all lanelets left of a given lanelet within the Route.

Note
The returned lanelets include lanelets that can be switched or not-switched to. The relations will be "left" and "adjacent_left" accordingly.
Parameters
laneletLanelet to get information about.
Returns
Relations to lanelets left of the input lanelet in the route. Nothing if 'lanelet' is not part of the route.

Definition at line 267 of file Route.cpp.

◆ length2d()

double lanelet::routing::Route::length2d ( ) const

Get the 2d length of the shortest path of this route.

Definition at line 188 of file Route.cpp.

◆ numLanes()

size_t lanelet::routing::Route::numLanes ( ) const

Returns the number of individual lanes.

Returns
Number of lanes

Definition at line 193 of file Route.cpp.

◆ operator=() [1/2]

Route& lanelet::routing::Route::operator= ( const Route other)
delete

◆ operator=() [2/2]

Route & lanelet::routing::Route::operator= ( Route &&  other)
defaultnoexcept

◆ previous()

ConstLanelets lanelet::routing::Route::previous ( const ConstLanelet lanelet) const

Similar to followingRelations but directly provides the following lanelets within the Route.

Definition at line 251 of file Route.cpp.

◆ previousRelations()

LaneletRelations lanelet::routing::Route::previousRelations ( const ConstLanelet lanelet) const

Provides information of the previous lanelets within the Route.

Parameters
laneletLanelet to get information about.
Returns
Relations to previous lanelets in the route. Nothing if 'lanelet' is not part of the route. The type will always be "successor".

Definition at line 243 of file Route.cpp.

◆ remainingLane()

LaneletSequence lanelet::routing::Route::remainingLane ( const ConstLanelet ll) const

Returns that remaining lane a Lanelet belongs to.

Parameters
llLanelet to get remaining lane for
Returns
All remaining lanelets of that lane. Nothing if Lanelet is not part of the route.

Definition at line 180 of file Route.cpp.

◆ remainingShortestPath()

LaneletPath lanelet::routing::Route::remainingShortestPath ( const ConstLanelet ll) const

Obtains the remaining shortest path to the destination. If the route is circular, the result will always have the same length and end before the lanelet passed as input argument.

Parameters
lla lanelet on the shortest path
Returns
shortest path where lanelet is the first element. Nothing if the lanelet is not on the shortest path.

Definition at line 140 of file Route.cpp.

◆ rightRelation()

Optional< LaneletRelation > lanelet::routing::Route::rightRelation ( const ConstLanelet lanelet) const

Provides information of the lanelet right of a given lanelet within the Route.

Note
The returned lanelet can include a lanelet that can be switched or not-switched to. The relation will be "right" and "adjacent_right" accordingly.
Parameters
laneletLanelet to get information about.
Returns
Relation to lanelet right of the input lanelet in the route. Nothing if 'lanelet' is not part of the route.

Definition at line 280 of file Route.cpp.

◆ rightRelations()

LaneletRelations lanelet::routing::Route::rightRelations ( const ConstLanelet lanelet) const

Provides information of the all lanelets right of a given lanelet within the Route.

Note
The returned lanelets include lanelets that can be switched or not-switched to. The relations will be "right" and "adjacent_right" accordingly.
Parameters
laneletLanelet to get information about.
Returns
Relations to lanelets right of the input lanelet in the route. Nothing if 'lanelet' is not part of the route.

Definition at line 288 of file Route.cpp.

◆ shortestPath()

const LaneletPath& lanelet::routing::Route::shortestPath ( ) const
inlinenoexcept

Returns the shortest path that was the base of this route.

Definition at line 51 of file Route.h.

◆ size()

size_t lanelet::routing::Route::size ( ) const

Number of Lanelets in the route.

Returns
Number of lanelets.

Definition at line 225 of file Route.cpp.

Member Data Documentation

◆ graph_

std::unique_ptr<internal::RouteGraph> lanelet::routing::Route::graph_
private

The internal graph.

Definition at line 202 of file Route.h.

◆ laneletSubmap_

LaneletSubmapConstPtr lanelet::routing::Route::laneletSubmap_
private

LaneletSubmap with all lanelets that are part of the route.

Definition at line 204 of file Route.h.

◆ shortestPath_

LaneletPath lanelet::routing::Route::shortestPath_
private

The underlying shortest path used to create the route.

Definition at line 203 of file Route.h.


The documentation for this class was generated from the following files:


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49