Main class of the routing module that holds routing information and can be queried. The RoutingGraph class is the central object of this module and is initialized with a LaneletMap, TrafficRules and RoutingCost. A routing graph with all interesting relations will be created for the traffic participant featured in the provided TrafficRules module. Routing costs will be calculated for each provided module. The routing graph can answer queries like "left", "following", "conflicting" lanelets, but also provide a shortest route or a Route. More...
#include <RoutingGraph.h>
Public Types | |
using | Configuration = std::map< std::string, Attribute > |
using | Errors = std::vector< std::string > |
For the checkValidity function. More... | |
Public Member Functions | |
Optional< ConstLanelet > | adjacentLeft (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get adjacent left (non-routable) lanelet of a given lanelet if it exists. More... | |
ConstLanelets | adjacentLefts (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get all adjacent left (non-routable) lanelets of a given lanelet if they exist. More... | |
Optional< ConstLanelet > | adjacentRight (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get adjacent right (non-routable) lanelet of a given lanelet if it exists. More... | |
ConstLanelets | adjacentRights (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get all adjacent right (non-routable) lanelets of a given lanelet if they exist. More... | |
ConstLanelets | besides (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Retrieve all reachable left and right lanelets. More... | |
Errors | checkValidity (bool throwOnError=true) const |
Performs some basic sanity checks. It is recommended to call this function after the routing graph has been generated since it can point out some mapping errors. More... | |
ConstLaneletOrAreas | conflicting (const ConstLaneletOrArea &laneletOrArea) const |
Retrieve all lanelets that are conflicting with the given lanelet. More... | |
void | exportGraphML (const std::string &filename, const RelationType &edgeTypesToExclude=RelationType::None, RoutingCostId routingCostId={}) const |
Export the internal graph to graphML (xml-based) file format. More... | |
void | exportGraphViz (const std::string &filename, const RelationType &edgeTypesToExclude=RelationType::None, RoutingCostId routingCostId={}) const |
Export the internal graph to graphViz (DOT) file format. This format includes coloring of the edges in the graph and bears little more information than graphML export. More... | |
ConstLanelets | following (const ConstLanelet &lanelet, bool withLaneChanges=false) const |
Returns the lanelets that can be reached from this lanelet. More... | |
LaneletRelations | followingRelations (const ConstLanelet &lanelet, bool withLaneChanges=false) const |
Returns the lanelets that can be reached from this lanelet and the relation. More... | |
void | forEachPredecessor (const ConstLanelet &lanelet, const LaneletVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const |
void | forEachPredecessorIncludingAreas (const ConstLaneletOrArea &lanelet, const LaneletOrAreaVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const |
Similar to RoutingGraph::forEachPredecessor but also includes areas into the search. More... | |
void | forEachSuccessor (const ConstLanelet &lanelet, const LaneletVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const |
Calls a function on every successor of lanelet, optionally including lane changes. More... | |
void | forEachSuccessorIncludingAreas (const ConstLaneletOrArea &lanelet, const LaneletOrAreaVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const |
Similar to RoutingGraph::forEachSuccessor but also includes areas into the search. More... | |
LaneletMapPtr | getDebugLaneletMap (RoutingCostId routingCostId={}, bool includeAdjacent=false, bool includeConflicting=false) const |
An abstract lanelet map holding the information of the routing graph. A good way to view the routing graph since it can be exported using the lanelet2_io module and there can be viewed in tools like JOSM. Each lanelet is represented by a point at the center of gravity of the lanelet. Relations are linestrings between points representing lanelets. More... | |
Optional< Route > | getRoute (const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const |
Get a driving route from 'start' to 'end' lanelet. More... | |
Optional< Route > | getRouteVia (const ConstLanelet &from, const ConstLanelets &via, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const |
Get a driving route from 'start' to 'end' lanelets while going via other lanelets. More... | |
Optional< ConstLanelet > | left (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get left (routable) lanelet of a given lanelet if it exists. More... | |
LaneletRelations | leftRelations (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Retrieve all lanelets and relations left of a given lanelet. More... | |
ConstLanelets | lefts (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get all left (routable) lanelets of a given lanelet if they exist. More... | |
RoutingGraph & | operator= (const RoutingGraph &)=delete |
RoutingGraph & | operator= (RoutingGraph &&) noexcept |
LaneletMapConstPtr | passableMap () const noexcept |
LaneletSubmap that includes all passable lanelets and areas. This map contains all passable lanelets and areas with all primitives (linestrings, points), including regulatory elements and lanelets referenced by them. It can be used to perform spacial queries e.g. for localization. When selecting a lanelet from this map please be aware that the routing graph may also contain the inverted lanelet. More... | |
LaneletSubmapConstPtr | passableSubmap () const noexcept |
Returns a submap that contains all lanelets and areas within this routing graph, and nothing else. You can obtain a full map of the routing graph by calling passabelSubmap()->laneletMap(), which ist a potentially costly operation. More... | |
LaneletPaths | possiblePaths (const ConstLanelet &startPoint, const PossiblePathsParams ¶ms) const |
Determines possible routes from a given start lanelet that satisfy the configuration in PossiblePathsParams. More... | |
LaneletPaths | possiblePaths (const ConstLanelet &startPoint, double minRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=false) const |
Determines possible routes from a given start lanelet that are "minRoutingCost"-long. More... | |
LaneletPaths | possiblePaths (const ConstLanelet &startPoint, uint32_t minLanelets, bool allowLaneChanges=false, RoutingCostId routingCostId={}) const |
Determines possible paths from a given start lanelet that are "minLanelets"-long. More... | |
LaneletOrAreaPaths | possiblePathsIncludingAreas (const ConstLaneletOrArea &startPoint, const PossiblePathsParams ¶ms) const |
Similar to RoutingGraph::possiblePaths, but also considers areas. More... | |
LaneletOrAreaPaths | possiblePathsIncludingAreas (const ConstLaneletOrArea &startPoint, double minRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=false) const |
Similar to RoutingGraph::possiblePaths, but also considers areas. More... | |
LaneletOrAreaPaths | possiblePathsIncludingAreas (const ConstLaneletOrArea &startPoint, uint32_t minElements, bool allowLaneChanges=false, RoutingCostId routingCostId={}) const |
Similar to RoutingGraph::possiblePaths, but also considers areas. More... | |
LaneletPaths | possiblePathsTowards (const ConstLanelet &targetLanelet, const PossiblePathsParams ¶ms) const |
Determines possible routes to reach the given lanelet which satisfy the configuration in PossiblePathsParams. More... | |
LaneletPaths | possiblePathsTowards (const ConstLanelet &targetLanelet, double minRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=false) const |
Determines possible routes that reach the given lanelet and are "minRoutingCost" long. More... | |
LaneletPaths | possiblePathsTowards (const ConstLanelet &targetLanelet, uint32_t minLanelets, bool allowLaneChanges=false, RoutingCostId routingCostId={}) const |
Determines possible paths towards a destination lanelet that are "minLanelets"-long. More... | |
ConstLanelets | previous (const ConstLanelet &lanelet, bool withLaneChanges=false) const |
Returns the possible previous lanelets of this lanelet. More... | |
LaneletRelations | previousRelations (const ConstLanelet &lanelet, bool withLaneChanges=false) const |
Returns the possible previous lanelets of this lanelet and the relation. More... | |
ConstLanelets | reachableSet (const ConstLanelet &lanelet, double maxRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=true) const |
Retrieve a set of lanelets that can be reached from a given lanelet. More... | |
ConstLaneletOrAreas | reachableSetIncludingAreas (const ConstLaneletOrArea &llOrAr, double maxRoutingCost, RoutingCostId routingCostId={}) const |
Retrieve set of lanelet or areas that are reachable without exceeding routing cost. More... | |
ConstLanelets | reachableSetTowards (const ConstLanelet &lanelet, double maxRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=true) const |
Retrieve a set of lanelets that can reach a given lanelet. More... | |
Optional< ConstLanelet > | right (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get right (routable) lanelet of a given lanelet if it exists. More... | |
LaneletRelations | rightRelations (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Retrieve all lanelets and relations right of a given lanelet. More... | |
ConstLanelets | rights (const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const |
Get all right (routable) lanelets of a given lanelet if they exist. More... | |
RoutingGraph ()=delete | |
The graph can not be copied, only moved. More... | |
RoutingGraph (const RoutingGraph &)=delete | |
RoutingGraph (RoutingGraph &&) noexcept | |
RoutingGraph (std::unique_ptr< internal::RoutingGraphGraph > &&graph, lanelet::LaneletSubmapConstPtr &&passableMap) | |
Optional< RelationType > | routingRelation (const ConstLanelet &from, const ConstLanelet &to, bool includeConflicting=false) const |
Determines the relation between two lanelets. More... | |
Optional< LaneletPath > | shortestPath (const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const |
Retrieve a shortest path between 'start' and 'end'. More... | |
Optional< LaneletOrAreaPath > | shortestPathIncludingAreas (const ConstLaneletOrArea &from, const ConstLaneletOrArea &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const |
Retrieve a shortest path between 'start' and 'end' that may contain Areas. More... | |
Optional< LaneletOrAreaPath > | shortestPathIncludingAreasVia (const ConstLaneletOrArea &start, const ConstLaneletOrAreas &via, const ConstLaneletOrArea &end, RoutingCostId routingCostId={}, bool withLaneChanges=true) const |
Retrieve a shortest path between 'start' and 'end' using intermediate points. Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, i.e. lanelets that are parallel and not only adjacent. More... | |
Optional< LaneletPath > | shortestPathVia (const ConstLanelet &start, const ConstLanelets &via, const ConstLanelet &end, RoutingCostId routingCostId={}, bool withLaneChanges=true) const |
Retrieve a shortest path between 'start' and 'end' using intermediate points. Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, i.e. lanelets that are parallel and not only adjacent. More... | |
~RoutingGraph () | |
Static Public Member Functions | |
static RoutingGraphUPtr | build (const LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration()) |
Main constructor with optional configuration. More... | |
static RoutingGraphUPtr | build (const LaneletSubmap &laneletSubmap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration()) |
Similar to the above but for a LaneletSubmap. More... | |
Static Public Attributes | |
static constexpr const char | ParticipantHeight [] = "participant_height" |
Defined configuration attributes. More... | |
Private Attributes | |
std::unique_ptr< internal::RoutingGraphGraph > | graph_ |
Documentation to be found in the cpp file. More... | |
LaneletSubmapConstPtr | passableLaneletSubmap_ |
Lanelet map of all passable lanelets. More... | |
Main class of the routing module that holds routing information and can be queried. The RoutingGraph class is the central object of this module and is initialized with a LaneletMap, TrafficRules and RoutingCost. A routing graph with all interesting relations will be created for the traffic participant featured in the provided TrafficRules module. Routing costs will be calculated for each provided module. The routing graph can answer queries like "left", "following", "conflicting" lanelets, but also provide a shortest route or a Route.
Definition at line 69 of file RoutingGraph.h.
using lanelet::routing::RoutingGraph::Configuration = std::map<std::string, Attribute> |
Used to provide a configuration
Definition at line 72 of file RoutingGraph.h.
using lanelet::routing::RoutingGraph::Errors = std::vector<std::string> |
For the checkValidity function.
Definition at line 71 of file RoutingGraph.h.
|
delete |
The graph can not be copied, only moved.
|
delete |
|
defaultnoexcept |
|
default |
lanelet::routing::RoutingGraph::RoutingGraph | ( | std::unique_ptr< internal::RoutingGraphGraph > && | graph, |
lanelet::LaneletSubmapConstPtr && | passableMap | ||
) |
Constructs the routing graph. Don't call this directly, use RoutingGraph::build instead.
Optional< ConstLanelet > lanelet::routing::RoutingGraph::adjacentLeft | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get adjacent left (non-routable) lanelet of a given lanelet if it exists.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 497 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::adjacentLefts | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get all adjacent left (non-routable) lanelets of a given lanelet if they exist.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 518 of file RoutingGraph.cpp.
Optional< ConstLanelet > lanelet::routing::RoutingGraph::adjacentRight | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get adjacent right (non-routable) lanelet of a given lanelet if it exists.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 508 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::adjacentRights | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get all adjacent right (non-routable) lanelets of a given lanelet if they exist.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 546 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::besides | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Retrieve all reachable left and right lanelets.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 480 of file RoutingGraph.cpp.
|
static |
Main constructor with optional configuration.
laneletMap | Map that should be used to build the graph |
trafficRules | Traffic rules that apply to find passable lanelets |
routingCosts | One or more ways to calculate routing costs |
config | Optional configuration |
Definition at line 375 of file RoutingGraph.cpp.
|
static |
Similar to the above but for a LaneletSubmap.
Definition at line 380 of file RoutingGraph.cpp.
RoutingGraph::Errors lanelet::routing::RoutingGraph::checkValidity | ( | bool | throwOnError = true | ) | const |
Performs some basic sanity checks. It is recommended to call this function after the routing graph has been generated since it can point out some mapping errors.
RoutingGraphError | if an error is found an 'throwOnError' is true |
throwOnError | Decide wheter to throw an exception or just return the errors |
Definition at line 855 of file RoutingGraph.cpp.
ConstLaneletOrAreas lanelet::routing::RoutingGraph::conflicting | ( | const ConstLaneletOrArea & | laneletOrArea | ) | const |
Retrieve all lanelets that are conflicting with the given lanelet.
Conflicting means that their bounding boxes overlap and the height clearance is smaller than the specified "participant_height".
laneletOrArea | Lanelet/Area to get conflicting lanelets for. |
Definition at line 570 of file RoutingGraph.cpp.
void lanelet::routing::RoutingGraph::exportGraphML | ( | const std::string & | filename, |
const RelationType & | edgeTypesToExclude = RelationType::None , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Export the internal graph to graphML (xml-based) file format.
filename | Fully qualified file name - ideally with extension (.graphml) |
edgeTypesToExclude | Exclude the specified relations. E.g. conflicting. Combine them with "|". |
routingCostId | ID of the routing cost module |
Definition at line 736 of file RoutingGraph.cpp.
void lanelet::routing::RoutingGraph::exportGraphViz | ( | const std::string & | filename, |
const RelationType & | edgeTypesToExclude = RelationType::None , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Export the internal graph to graphViz (DOT) file format. This format includes coloring of the edges in the graph and bears little more information than graphML export.
filename | Fully qualified file name - ideally with extension (.gv) |
edgeTypesToExclude | Exclude the specified relations. E.g. conflicting. Combine them with "|". |
routingCostId | ID of the routing cost module |
Definition at line 748 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::following | ( | const ConstLanelet & | lanelet, |
bool | withLaneChanges = false |
||
) | const |
Returns the lanelets that can be reached from this lanelet.
lanelet | Start lanelet |
withLaneChanges | Include left and right lanes or not |
Definition at line 446 of file RoutingGraph.cpp.
LaneletRelations lanelet::routing::RoutingGraph::followingRelations | ( | const ConstLanelet & | lanelet, |
bool | withLaneChanges = false |
||
) | const |
Returns the lanelets that can be reached from this lanelet and the relation.
lanelet | Start lanelet |
withLaneChanges | Include left and right lanes or not |
Definition at line 451 of file RoutingGraph.cpp.
void lanelet::routing::RoutingGraph::forEachPredecessor | ( | const ConstLanelet & | lanelet, |
const LaneletVisitFunction & | f, | ||
bool | allowLaneChanges = true , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Similar to RoutingGraph::forEachSuccessor but goes backwards in the routing graph instead of forward. The LaneletVisitInformation::cost will still be positive, despite going backwards.
Definition at line 702 of file RoutingGraph.cpp.
void lanelet::routing::RoutingGraph::forEachPredecessorIncludingAreas | ( | const ConstLaneletOrArea & | lanelet, |
const LaneletOrAreaVisitFunction & | f, | ||
bool | allowLaneChanges = true , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Similar to RoutingGraph::forEachPredecessor but also includes areas into the search.
Definition at line 718 of file RoutingGraph.cpp.
void lanelet::routing::RoutingGraph::forEachSuccessor | ( | const ConstLanelet & | lanelet, |
const LaneletVisitFunction & | f, | ||
bool | allowLaneChanges = true , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Calls a function on every successor of lanelet, optionally including lane changes.
This function can be used to query the routing graph on a more direct level. The function will be called on lanelets with monotonically increasing cost from the start lanelet, including the start lanelet itself. If the function returns "false" on an input, its followers will not be visited through this lanelet, as if it did not exist.
The search internally uses the dijkstra algorithm in order to discover the shortest path to the successors of this lanelet and calls the provided function once it is known.
In order to abort the query early, an exception can be thrown. If the lanelet is not part of the graph, nothing will be called.
lanelet | the lanelet where the search starts |
f | the function to be called on lanelet and its successors |
allowLaneChanges | also consider lane changes |
routingCostId | id for the routing cost module that is used to calculate the shortest path |
Definition at line 671 of file RoutingGraph.cpp.
void lanelet::routing::RoutingGraph::forEachSuccessorIncludingAreas | ( | const ConstLaneletOrArea & | lanelet, |
const LaneletOrAreaVisitFunction & | f, | ||
bool | allowLaneChanges = true , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Similar to RoutingGraph::forEachSuccessor but also includes areas into the search.
Definition at line 685 of file RoutingGraph.cpp.
LaneletMapPtr lanelet::routing::RoutingGraph::getDebugLaneletMap | ( | RoutingCostId | routingCostId = {} , |
bool | includeAdjacent = false , |
||
bool | includeConflicting = false |
||
) | const |
An abstract lanelet map holding the information of the routing graph. A good way to view the routing graph since it can be exported using the lanelet2_io module and there can be viewed in tools like JOSM. Each lanelet is represented by a point at the center of gravity of the lanelet. Relations are linestrings between points representing lanelets.
routingCostId | ID of the routing cost module used for the cost assignment |
includeAdjacent | Also include adjacent (non-routable) relations |
includeConflicting | Also include conflicting relations |
Definition at line 844 of file RoutingGraph.cpp.
Optional< Route > lanelet::routing::RoutingGraph::getRoute | ( | const ConstLanelet & | from, |
const ConstLanelet & | to, | ||
RoutingCostId | routingCostId = {} , |
||
bool | withLaneChanges = true |
||
) | const |
Get a driving route from 'start' to 'end' lanelet.
from | Start lanelet to find a shortest path |
to | End lanelet to find a shortest path |
routingCostId | ID of RoutingCost module to determine shortest route |
withLaneChanges | if false, the shortest path will not contain lane changes and the route will only contain lanelets that are reachable without lane changes |
Definition at line 386 of file RoutingGraph.cpp.
Optional< Route > lanelet::routing::RoutingGraph::getRouteVia | ( | const ConstLanelet & | from, |
const ConstLanelets & | via, | ||
const ConstLanelet & | to, | ||
RoutingCostId | routingCostId = {} , |
||
bool | withLaneChanges = true |
||
) | const |
Get a driving route from 'start' to 'end' lanelets while going via other lanelets.
from | Start lanelet to find a shortest path |
via | Other lanelets to visit (in this order) |
to | End lanelet to find a shortest path |
routingCostId | ID of RoutingCost module to determine shortest route |
withLaneChanges | if false, the shortest path will not contain lane changes and the route will only contain lanelets that are reachable without lane changes |
If from and to are the same lanelet, the resulting route will form a loop.
Definition at line 395 of file RoutingGraph.cpp.
Optional< ConstLanelet > lanelet::routing::RoutingGraph::left | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get left (routable) lanelet of a given lanelet if it exists.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 492 of file RoutingGraph.cpp.
LaneletRelations lanelet::routing::RoutingGraph::leftRelations | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Retrieve all lanelets and relations left of a given lanelet.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 522 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::lefts | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get all left (routable) lanelets of a given lanelet if they exist.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 514 of file RoutingGraph.cpp.
|
delete |
|
defaultnoexcept |
|
inlinenoexcept |
LaneletSubmap that includes all passable lanelets and areas. This map contains all passable lanelets and areas with all primitives (linestrings, points), including regulatory elements and lanelets referenced by them. It can be used to perform spacial queries e.g. for localization. When selecting a lanelet from this map please be aware that the routing graph may also contain the inverted lanelet.
This function is deprecated because it was misleading that the map also contained lanelets referenced by regulatory elements and not only the lanelets from the routing graph.
Definition at line 476 of file RoutingGraph.h.
|
inlinenoexcept |
Returns a submap that contains all lanelets and areas within this routing graph, and nothing else. You can obtain a full map of the routing graph by calling passabelSubmap()->laneletMap(), which ist a potentially costly operation.
Definition at line 463 of file RoutingGraph.h.
LaneletPaths lanelet::routing::RoutingGraph::possiblePaths | ( | const ConstLanelet & | startPoint, |
const PossiblePathsParams & | params | ||
) | const |
Determines possible routes from a given start lanelet that satisfy the configuration in PossiblePathsParams.
startPoint | Start lanelet |
params | Parameters that configure the behaviour of the algorithm; see doc on PossiblePathsParams for details. |
InvalidInputError | if neither elementLimit nor costLimit is valid in params |
Definition at line 604 of file RoutingGraph.cpp.
LaneletPaths lanelet::routing::RoutingGraph::possiblePaths | ( | const ConstLanelet & | startPoint, |
double | minRoutingCost, | ||
RoutingCostId | routingCostId = {} , |
||
bool | allowLaneChanges = false |
||
) | const |
Determines possible routes from a given start lanelet that are "minRoutingCost"-long.
This behaves exactly as the PossiblePathsParams version with params.costLimit=minRoutingCost, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
Definition at line 614 of file RoutingGraph.cpp.
LaneletPaths lanelet::routing::RoutingGraph::possiblePaths | ( | const ConstLanelet & | startPoint, |
uint32_t | minLanelets, | ||
bool | allowLaneChanges = false , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Determines possible paths from a given start lanelet that are "minLanelets"-long.
This behaves exactly as the PossiblePathsParams version with params.elementLimit=minLanelets, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
Definition at line 619 of file RoutingGraph.cpp.
LaneletOrAreaPaths lanelet::routing::RoutingGraph::possiblePathsIncludingAreas | ( | const ConstLaneletOrArea & | startPoint, |
const PossiblePathsParams & | params | ||
) | const |
Similar to RoutingGraph::possiblePaths, but also considers areas.
Definition at line 647 of file RoutingGraph.cpp.
LaneletOrAreaPaths lanelet::routing::RoutingGraph::possiblePathsIncludingAreas | ( | const ConstLaneletOrArea & | startPoint, |
double | minRoutingCost, | ||
RoutingCostId | routingCostId = {} , |
||
bool | allowLaneChanges = false |
||
) | const |
Similar to RoutingGraph::possiblePaths, but also considers areas.
Definition at line 658 of file RoutingGraph.cpp.
LaneletOrAreaPaths lanelet::routing::RoutingGraph::possiblePathsIncludingAreas | ( | const ConstLaneletOrArea & | startPoint, |
uint32_t | minElements, | ||
bool | allowLaneChanges = false , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Similar to RoutingGraph::possiblePaths, but also considers areas.
Definition at line 665 of file RoutingGraph.cpp.
LaneletPaths lanelet::routing::RoutingGraph::possiblePathsTowards | ( | const ConstLanelet & | targetLanelet, |
const PossiblePathsParams & | params | ||
) | const |
Determines possible routes to reach the given lanelet which satisfy the configuration in PossiblePathsParams.
targetLanelet | Destination lanelet |
params | Parameters that configure the behaviour of the algorithm; see doc on PossiblePathsParams for details. |
InvalidInputError | if neither elementLimit nor costLimit is valid in params |
Definition at line 624 of file RoutingGraph.cpp.
LaneletPaths lanelet::routing::RoutingGraph::possiblePathsTowards | ( | const ConstLanelet & | targetLanelet, |
double | minRoutingCost, | ||
RoutingCostId | routingCostId = {} , |
||
bool | allowLaneChanges = false |
||
) | const |
Determines possible routes that reach the given lanelet and are "minRoutingCost" long.
This behaves exactly as the PossiblePathsParams version with params.costLimit=minRoutingCost, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
Definition at line 635 of file RoutingGraph.cpp.
LaneletPaths lanelet::routing::RoutingGraph::possiblePathsTowards | ( | const ConstLanelet & | targetLanelet, |
uint32_t | minLanelets, | ||
bool | allowLaneChanges = false , |
||
RoutingCostId | routingCostId = {} |
||
) | const |
Determines possible paths towards a destination lanelet that are "minLanelets"-long.
This behaves exactly as the PossiblePathsParams version with params.elementLimit=minLanelets, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
Definition at line 641 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::previous | ( | const ConstLanelet & | lanelet, |
bool | withLaneChanges = false |
||
) | const |
Returns the possible previous lanelets of this lanelet.
lanelet | Start lanelet |
withLaneChanges | Include left and right lanes or not |
Definition at line 460 of file RoutingGraph.cpp.
LaneletRelations lanelet::routing::RoutingGraph::previousRelations | ( | const ConstLanelet & | lanelet, |
bool | withLaneChanges = false |
||
) | const |
Returns the possible previous lanelets of this lanelet and the relation.
lanelet | Start lanelet |
withLaneChanges | Include left and right lanes or not |
Definition at line 465 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::reachableSet | ( | const ConstLanelet & | lanelet, |
double | maxRoutingCost, | ||
RoutingCostId | routingCostId = {} , |
||
bool | allowLaneChanges = true |
||
) | const |
Retrieve a set of lanelets that can be reached from a given lanelet.
Determines which lanelets can be reached from a give start lanelets within a given amount of routing cost.
lanelet | Start lanelet |
maxRoutingCost | Maximum amount of routing cost allowed to reach other lanelets |
routingCostId | ID of the routing cost module used for routing cost. |
allowLaneChanges | Allow or forbid lane changes |
Definition at line 574 of file RoutingGraph.cpp.
ConstLaneletOrAreas lanelet::routing::RoutingGraph::reachableSetIncludingAreas | ( | const ConstLaneletOrArea & | llOrAr, |
double | maxRoutingCost, | ||
RoutingCostId | routingCostId = {} |
||
) | const |
Retrieve set of lanelet or areas that are reachable without exceeding routing cost.
Definition at line 584 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::reachableSetTowards | ( | const ConstLanelet & | lanelet, |
double | maxRoutingCost, | ||
RoutingCostId | routingCostId = {} , |
||
bool | allowLaneChanges = true |
||
) | const |
Retrieve a set of lanelets that can reach a given lanelet.
Determines which reach the given lanelet with a given amount of routing cost.
lanelet | destination lanelet |
maxRoutingCost | Maximum amount of routing cost allowed to reach other lanelets |
routingCostId | ID of the routing cost module used for routing cost. |
allowLaneChanges | Allow or forbid lane changes |
Definition at line 594 of file RoutingGraph.cpp.
Optional< ConstLanelet > lanelet::routing::RoutingGraph::right | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get right (routable) lanelet of a given lanelet if it exists.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 503 of file RoutingGraph.cpp.
LaneletRelations lanelet::routing::RoutingGraph::rightRelations | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Retrieve all lanelets and relations right of a given lanelet.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 550 of file RoutingGraph.cpp.
ConstLanelets lanelet::routing::RoutingGraph::rights | ( | const ConstLanelet & | lanelet, |
RoutingCostId | routingCostId = {} |
||
) | const |
Get all right (routable) lanelets of a given lanelet if they exist.
lanelet | Start lanelet |
routingCostId | the routing cost module to be used. Can make a difference if one allows a lane change but the other one doesn't. |
Definition at line 542 of file RoutingGraph.cpp.
Optional< RelationType > lanelet::routing::RoutingGraph::routingRelation | ( | const ConstLanelet & | from, |
const ConstLanelet & | to, | ||
bool | includeConflicting = false |
||
) | const |
Determines the relation between two lanelets.
from | Start lanelet |
to | Goal lanelet |
includeConflicting | if false, conflicting lanelets are not considered as relations |
Definition at line 436 of file RoutingGraph.cpp.
Optional< LaneletPath > lanelet::routing::RoutingGraph::shortestPath | ( | const ConstLanelet & | from, |
const ConstLanelet & | to, | ||
RoutingCostId | routingCostId = {} , |
||
bool | withLaneChanges = true |
||
) | const |
Retrieve a shortest path between 'start' and 'end'.
Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, i.e. lanelets that are parallel and not only adjacent.
from | Start lanelet to find a shortest path |
to | End lanelet to find a shortest path |
routingCostId | ID of RoutingCost module to determine shortest path |
withLaneChanges | if false, the shortest path will not contain lane changes |
Definition at line 404 of file RoutingGraph.cpp.
Optional< LaneletOrAreaPath > lanelet::routing::RoutingGraph::shortestPathIncludingAreas | ( | const ConstLaneletOrArea & | from, |
const ConstLaneletOrArea & | to, | ||
RoutingCostId | routingCostId = {} , |
||
bool | withLaneChanges = true |
||
) | const |
Retrieve a shortest path between 'start' and 'end' that may contain Areas.
Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, i.e. lanelets that are parallel and not only adjacent.
from | Start lanelet or area to find a shortest path |
to | End lanelet or area to find a shortest path to |
routingCostId | ID of RoutingCost module to determine shortest path |
withLaneChanges | if false, the shortest path will not contain lane changes |
Definition at line 409 of file RoutingGraph.cpp.
Optional< LaneletOrAreaPath > lanelet::routing::RoutingGraph::shortestPathIncludingAreasVia | ( | const ConstLaneletOrArea & | start, |
const ConstLaneletOrAreas & | via, | ||
const ConstLaneletOrArea & | end, | ||
RoutingCostId | routingCostId = {} , |
||
bool | withLaneChanges = true |
||
) | const |
Retrieve a shortest path between 'start' and 'end' using intermediate points. Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, i.e. lanelets that are parallel and not only adjacent.
start | Start lanelet or area to find a shortest path |
via | Intermediate lanelets or areas that have to be passed |
end | End lanelet or area to find a shortest path |
routingCostId | ID of RoutingCost module to determine shortest path |
withLaneChanges | if false, the shortest path will not contain lane changes |
Definition at line 425 of file RoutingGraph.cpp.
Optional< LaneletPath > lanelet::routing::RoutingGraph::shortestPathVia | ( | const ConstLanelet & | start, |
const ConstLanelets & | via, | ||
const ConstLanelet & | end, | ||
RoutingCostId | routingCostId = {} , |
||
bool | withLaneChanges = true |
||
) | const |
Retrieve a shortest path between 'start' and 'end' using intermediate points. Will find a shortest path using Djikstra's shortest path algorithm and the routing cost calculated by the routing cost module with the respective ID. Be aware that the shortest path may contain lane changes, i.e. lanelets that are parallel and not only adjacent.
start | Start lanelet to find a shortest path |
via | Intermediate lanelets that have to be passed |
end | End lanelet to find a shortest path |
routingCostId | ID of RoutingCost module to determine shortest path |
withLaneChanges | if false, the shortest path will not contain lane changes |
Definition at line 417 of file RoutingGraph.cpp.
|
private |
Documentation to be found in the cpp file.
Wrapper of the routing graph
Definition at line 495 of file RoutingGraph.h.
|
staticconstexpr |
Defined configuration attributes.
Definition at line 74 of file RoutingGraph.h.
|
private |
Lanelet map of all passable lanelets.
Definition at line 496 of file RoutingGraph.h.