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

Container to associate multiple routing graphs to allow queries on multiple graphs. More...

#include <RoutingGraphContainer.h>

Public Types

using ConflictingInGraph = std::pair< size_t, ConstLanelets >
 id of conflicing graph, lanelets in conflict there More...
 
using ConflictingInGraphs = std::vector< ConflictingInGraph >
 

Public Member Functions

ConstLanelets conflictingInGraph (const ConstLanelet &lanelet, size_t routingGraphId, double participantHeight=.0) const
 Find the conflicting lanelets of a given lanelet within a specified graph. More...
 
ConflictingInGraphs conflictingInGraphs (const ConstLanelet &lanelet, double participantHeight=.0) const
 Find the conflicting lanelets of a given lanelet within all graphs. More...
 
ConstLanelets conflictingOfRouteInGraph (const Route *route, size_t routingGraphId, double participantHeight=.0) const
 Find the conflicting lanelets of a given route within a specified graph. More...
 
ConflictingInGraphs conflictingOfRouteInGraphs (const Route *route, double participantHeight=.0) const
 Find the conflicting lanelets of a given route within all graphs. More...
 
 RoutingGraphContainer (const std::vector< RoutingGraphPtr > &routingGraphs)
 Constructor of routing graph container. More...
 
 RoutingGraphContainer (std::vector< RoutingGraphConstPtr > routingGraphs)
 Constructor of routing graph container. More...
 
const std::vector< RoutingGraphConstPtr > & routingGraphs () const
 Returns the routing graphs stored in the container. More...
 

Private Attributes

std::vector< RoutingGraphConstPtrgraphs_
 Routing graphs of the container. More...
 

Detailed Description

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.

Definition at line 20 of file RoutingGraphContainer.h.

Member Typedef Documentation

◆ ConflictingInGraph

id of conflicing graph, lanelets in conflict there

Definition at line 22 of file RoutingGraphContainer.h.

◆ ConflictingInGraphs

Definition at line 23 of file RoutingGraphContainer.h.

Constructor & Destructor Documentation

◆ RoutingGraphContainer() [1/2]

lanelet::routing::RoutingGraphContainer::RoutingGraphContainer ( std::vector< RoutingGraphConstPtr routingGraphs)
inlineexplicit

Constructor of routing graph container.

Parameters
routingGraphsThe routing graphs that should be used in the container

Definition at line 27 of file RoutingGraphContainer.h.

◆ RoutingGraphContainer() [2/2]

lanelet::routing::RoutingGraphContainer::RoutingGraphContainer ( const std::vector< RoutingGraphPtr > &  routingGraphs)
inlineexplicit

Constructor of routing graph container.

Parameters
routingGraphsThe routing graphs that should be used in the container

Definition at line 31 of file RoutingGraphContainer.h.

Member Function Documentation

◆ conflictingInGraph()

ConstLanelets lanelet::routing::RoutingGraphContainer::conflictingInGraph ( const ConstLanelet lanelet,
size_t  routingGraphId,
double  participantHeight = .0 
) const
inline

Find the conflicting lanelets of a given lanelet within a specified graph.

Parameters
laneletFind conflicting ones for this lanelet
routingGraphIdID/position in vector of the routing graph
participantHeightOptional height of the participant
Returns
Conflicting lanelets within that graph
Exceptions
InvalidInputErrorif the routingGraphId is too high

Definition at line 40 of file RoutingGraphContainer.h.

◆ conflictingInGraphs()

ConflictingInGraphs lanelet::routing::RoutingGraphContainer::conflictingInGraphs ( const ConstLanelet lanelet,
double  participantHeight = .0 
) const
inline

Find the conflicting lanelets of a given lanelet within all graphs.

Parameters
laneletFind conflicting ones for this lanelet
participantHeightOptional height of the participant
Returns
Conflicting lanelets within the graphs

Definition at line 63 of file RoutingGraphContainer.h.

◆ conflictingOfRouteInGraph()

ConstLanelets lanelet::routing::RoutingGraphContainer::conflictingOfRouteInGraph ( const Route route,
size_t  routingGraphId,
double  participantHeight = .0 
) const
inline

Find the conflicting lanelets of a given route within a specified graph.

Parameters
routeFind conflicting lanelets for all lanelets within this route
routingGraphIdID/position in vector of the routing graph
participantHeightOptional height of the participant
Returns
Conflicting lanelets within that graph to any lanelet within the route
Exceptions
InvalidInputErrorif the routingGraphId is too high

Definition at line 77 of file RoutingGraphContainer.h.

◆ conflictingOfRouteInGraphs()

ConflictingInGraphs lanelet::routing::RoutingGraphContainer::conflictingOfRouteInGraphs ( const Route route,
double  participantHeight = .0 
) const
inline

Find the conflicting lanelets of a given route within all graphs.

Parameters
routeFind conflicting lanelets for all lanelets within this route
participantHeightOptional height of the participant
Returns
Conflicting lanelets of each graph to any lanelet within the route

Definition at line 91 of file RoutingGraphContainer.h.

◆ routingGraphs()

const std::vector<RoutingGraphConstPtr>& lanelet::routing::RoutingGraphContainer::routingGraphs ( ) const
inline

Returns the routing graphs stored in the container.

Definition at line 100 of file RoutingGraphContainer.h.

Member Data Documentation

◆ graphs_

std::vector<RoutingGraphConstPtr> lanelet::routing::RoutingGraphContainer::graphs_
private

Routing graphs of the container.

Definition at line 103 of file RoutingGraphContainer.h.


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


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