Class RoutingGraph
Defined in File RoutingGraph.h
Class Documentation
-
class RoutingGraph
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.
Note
The direction of lanelets matters! ‘lanelet’ and ‘lanelet.invert()’ are differentiated since this matters when lanelets are passable in both directions.
Note
‘adjacent_left’ and ‘adjacent_right’ means that there is a passable lanelet left/right of another passable lanelet, but a lane change is not allowed.
Public Types
-
using Errors = std::vector<std::string>
For the checkValidity function.
-
using Configuration = std::map<std::string, Attribute>
Used to provide a configuration
Public Functions
-
RoutingGraph() = delete
The graph can not be copied, only moved.
-
RoutingGraph(const RoutingGraph&) = delete
-
RoutingGraph &operator=(const RoutingGraph&) = delete
-
RoutingGraph(RoutingGraph&&) noexcept
-
RoutingGraph &operator=(RoutingGraph&&) noexcept
-
~RoutingGraph()
-
Optional<Route> getRoute(const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId = {}, bool withLaneChanges = true) const
Get a driving route from ‘start’ to ‘end’ lanelet.
See also
- Parameters:
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
- Returns:
A route of all adjacent lanelets of the shortest route that lead to ‘end’. Nothing if there’s no route.
-
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.
If from and to are the same lanelet, the resulting route will form a loop.
See also
- Parameters:
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
- Returns:
A route of all adjacent lanelets of the shortest route that lead to ‘end’. Nothing if there’s not route.
-
Optional<LaneletPath> 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.
- Parameters:
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
-
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.
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.
- Parameters:
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
-
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.
See also
- Parameters:
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
-
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.
See also
- Parameters:
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
-
Optional<RelationType> routingRelation(const ConstLanelet &from, const ConstLanelet &to, bool includeConflicting = false) const
Determines the relation between two lanelets.
- Parameters:
from – Start lanelet
to – Goal lanelet
includeConflicting – if false, conflicting lanelets are not considered as relations
- Returns:
Relation between the lanelets or nothing if no relation exists. Nothing if at least one of the lanelets is not passable.
-
ConstLanelets following(const ConstLanelet &lanelet, bool withLaneChanges = false) const
Returns the lanelets that can be reached from this lanelet.
See also
- Parameters:
lanelet – Start lanelet
withLaneChanges – Include left and right lanes or not
- Returns:
Lanelets that can be directly reached
-
LaneletRelations followingRelations(const ConstLanelet &lanelet, bool withLaneChanges = false) const
Returns the lanelets that can be reached from this lanelet and the relation.
See also
- Parameters:
lanelet – Start lanelet
withLaneChanges – Include left and right lanes or not
- Returns:
Lanelets can be directly reached
-
ConstLanelets previous(const ConstLanelet &lanelet, bool withLaneChanges = false) const
Returns the possible previous lanelets of this lanelet.
See also
- Parameters:
lanelet – Start lanelet
withLaneChanges – Include left and right lanes or not
- Returns:
All previous lanelets
-
LaneletRelations previousRelations(const ConstLanelet &lanelet, bool withLaneChanges = false) const
Returns the possible previous lanelets of this lanelet and the relation.
See also
- Parameters:
lanelet – Start lanelet
withLaneChanges – Include left and right lanes or not
- Returns:
Lanelets that could be used to reach this lanelet
-
ConstLanelets besides(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Retrieve all reachable left and right lanelets.
- Parameters:
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.
- Returns:
All left and right lanelets that can be reached, including lanelet, ordered left to right.
-
Optional<ConstLanelet> left(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get left (routable) lanelet of a given lanelet if it exists.
See also
- Parameters:
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.
- Returns:
Left lanelet if it exists. Nothing if it doesn’t.
-
Optional<ConstLanelet> adjacentLeft(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get adjacent left (non-routable) lanelet of a given lanelet if it exists.
See also
- Parameters:
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.
- Returns:
Adjacent left lanelet if it exists. Nothing if it doesn’t.
-
Optional<ConstLanelet> right(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get right (routable) lanelet of a given lanelet if it exists.
See also
- Parameters:
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.
- Returns:
Right lanelet if it exists. Nothing if it doesn’t.
-
Optional<ConstLanelet> adjacentRight(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get adjacent right (non-routable) lanelet of a given lanelet if it exists.
See also
- Parameters:
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.
- Returns:
Adjacent right lanelet if it exists. Nothing if it doesn’t.
-
ConstLanelets lefts(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get all left (routable) lanelets of a given lanelet if they exist.
See also
- Parameters:
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.
- Returns:
Left lanelets if they exists. Empty if they don’t.
-
ConstLanelets adjacentLefts(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get all adjacent left (non-routable) lanelets of a given lanelet if they exist.
See also
- Parameters:
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.
- Returns:
Adjacent left lanelets if they exists. Empty if they don’t.
-
LaneletRelations leftRelations(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Retrieve all lanelets and relations left of a given lanelet.
See also
- Parameters:
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.
- Returns:
All lanelets and relations left of a given lanelet.
-
ConstLanelets rights(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get all right (routable) lanelets of a given lanelet if they exist.
See also
- Parameters:
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.
- Returns:
Right lanelets if they exists. Empty if they don’t.
-
ConstLanelets adjacentRights(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Get all adjacent right (non-routable) lanelets of a given lanelet if they exist.
See also
- Parameters:
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.
- Returns:
Adjacent right lanelets if they exists. Empty if they don’t.
-
LaneletRelations rightRelations(const ConstLanelet &lanelet, RoutingCostId routingCostId = {}) const
Retrieve all lanelets and relations right of a given lanelet.
See also
- Parameters:
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.
- Returns:
All lanelets and relations right of a given lanelet.
-
ConstLaneletOrAreas 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”.
- Parameters:
laneletOrArea – Lanelet/Area to get conflicting lanelets for.
- Returns:
All conflicting lanelets.
-
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.
Determines which lanelets can be reached from a give start lanelets within a given amount of routing cost.
- Parameters:
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
- Returns:
all lanelets that are reachable in no particular orders. “lanelet” itself is always included.
-
ConstLaneletOrAreas reachableSetIncludingAreas(const ConstLaneletOrArea &llOrAr, double maxRoutingCost, RoutingCostId routingCostId = {}) const
Retrieve set of lanelet or areas that are reachable without exceeding routing cost.
-
ConstLanelets 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.
- Parameters:
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
- Returns:
all lanelets in range in no particular order. “lanelet” itself is always included.
-
LaneletPaths possiblePaths(const ConstLanelet &startPoint, const PossiblePathsParams ¶ms) const
Determines possible routes from a given start lanelet that satisfy the configuration in PossiblePathsParams.
- Parameters:
startPoint – Start lanelet
params – Parameters that configure the behaviour of the algorithm; see doc on PossiblePathsParams for details.
- Throws:
InvalidInputError – if neither elementLimit nor costLimit is valid in params
- Returns:
all valid possible paths. If a lanelet can be reached using different paths, only the one is included that requires the least number of lane changes and has minimum routing costs. “startPoint” itself is always included if it is in the routing graph.
-
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.
This behaves exactly as the PossiblePathsParams version with params.costLimit=minRoutingCost, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
-
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.
This behaves exactly as the PossiblePathsParams version with params.elementLimit=minLanelets, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
-
LaneletPaths possiblePathsTowards(const ConstLanelet &targetLanelet, const PossiblePathsParams ¶ms) const
Determines possible routes to reach the given lanelet which satisfy the configuration in PossiblePathsParams.
- Parameters:
targetLanelet – Destination lanelet
params – Parameters that configure the behaviour of the algorithm; see doc on PossiblePathsParams for details.
- Throws:
InvalidInputError – if neither elementLimit nor costLimit is valid in params
- Returns:
possible paths that are at least as long as specified in ‘minRoutingCost’. “targetLanelet” itself is always included if it is in the routing graph.
-
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.
This behaves exactly as the PossiblePathsParams version with params.costLimit=minRoutingCost, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
-
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.
This behaves exactly as the PossiblePathsParams version with params.elementLimit=minLanelets, params.includeLaneChanges=allowLaneChanges and params.routingCostId=routingCostId (and the rest as default).
-
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea &startPoint, const PossiblePathsParams ¶ms) const
Similar to RoutingGraph::possiblePaths, but also considers areas.
-
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea &startPoint, double minRoutingCost, RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const
Similar to RoutingGraph::possiblePaths, but also considers areas.
-
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea &startPoint, uint32_t minElements, bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const
Similar to RoutingGraph::possiblePaths, but also considers areas.
-
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.
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.
- Parameters:
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
-
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.
-
void 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.
-
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.
-
void exportGraphML(const std::string &filename, const RelationType &edgeTypesToExclude = RelationType::None, RoutingCostId routingCostId = {}) const
Export the internal graph to graphML (xml-based) file format.
See also
- Parameters:
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
-
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.
- Parameters:
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
-
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.
- Parameters:
routingCostId – ID of the routing cost module used for the cost assignment
includeAdjacent – Also include adjacent (non-routable) relations
includeConflicting – Also include conflicting relations
- Returns:
LaneletMap with the requested information
-
inline 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.
-
inline 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.
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.
- Returns:
LaneletMap with all passable lanelets and areas
-
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.
- Throws:
RoutingGraphError – if an error is found an ‘throwOnError’ is true
- Parameters:
throwOnError – Decide wheter to throw an exception or just return the errors
- Returns:
Possible errors if ‘throwOnError’ is false.
-
RoutingGraph(std::unique_ptr<internal::RoutingGraphGraph> &&graph, lanelet::LaneletSubmapConstPtr &&passableMap)
Constructs the routing graph. Don’t call this directly, use RoutingGraph::build instead.
Public Static 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.
- Parameters:
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
-
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.
Public Static Attributes
-
static constexpr const char ParticipantHeight[] = "participant_height"
Defined configuration attributes.
-
using Errors = std::vector<std::string>