Class RoutingGraphContainer
Defined in File RoutingGraphContainer.h
Class Documentation
-
class RoutingGraphContainer
Container to associate multiple routing graphs to allow queries on multiple graphs.
Note
We cannot use the ‘conflicting’ relations that have been determined when creating the individual graphs because they used their respective height in 3D (e.g. 2m for a pedestrian), but the participant we want to query for could be taller (e.g. 4m truck). Therefore we can’t rely on that.
Public Types
-
using ConflictingInGraph = std::pair<size_t, ConstLanelets>
id of conflicing graph, lanelets in conflict there
-
using ConflictingInGraphs = std::vector<ConflictingInGraph>
Public Functions
-
inline explicit RoutingGraphContainer(std::vector<RoutingGraphConstPtr> routingGraphs)
Constructor of routing graph container.
- Parameters:
routingGraphs – The routing graphs that should be used in the container
-
inline explicit RoutingGraphContainer(const std::vector<RoutingGraphPtr> &routingGraphs)
Constructor of routing graph container.
- Parameters:
routingGraphs – The routing graphs that should be used in the container
-
inline ConstLanelets conflictingInGraph(const ConstLanelet &lanelet, size_t routingGraphId, double participantHeight = .0) const
Find the conflicting lanelets of a given lanelet within a specified graph.
- Parameters:
lanelet – Find conflicting ones for this lanelet
routingGraphId – ID/position in vector of the routing graph
participantHeight – Optional height of the participant
- Throws:
InvalidInputError – if the routingGraphId is too high
- Returns:
Conflicting lanelets within that graph
-
inline ConflictingInGraphs conflictingInGraphs(const ConstLanelet &lanelet, double participantHeight = .0) const
Find the conflicting lanelets of a given lanelet within all graphs.
- Parameters:
lanelet – Find conflicting ones for this lanelet
participantHeight – Optional height of the participant
- Returns:
Conflicting lanelets within the graphs
-
inline ConstLanelets conflictingOfRouteInGraph(const Route *route, size_t routingGraphId, double participantHeight = .0) const
Find the conflicting lanelets of a given route within a specified graph.
- Parameters:
route – Find conflicting lanelets for all lanelets within this route
routingGraphId – ID/position in vector of the routing graph
participantHeight – Optional height of the participant
- Throws:
InvalidInputError – if the routingGraphId is too high
- Returns:
Conflicting lanelets within that graph to any lanelet within the route
-
inline ConflictingInGraphs conflictingOfRouteInGraphs(const Route *route, double participantHeight = .0) const
Find the conflicting lanelets of a given route within all graphs.
- Parameters:
route – Find conflicting lanelets for all lanelets within this route
participantHeight – Optional height of the participant
- Returns:
Conflicting lanelets of each graph to any lanelet within the route
-
inline const std::vector<RoutingGraphConstPtr> &routingGraphs() const
Returns the routing graphs stored in the container.
-
using ConflictingInGraph = std::pair<size_t, ConstLanelets>