Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
lanelet::routing::internal::Graph< BaseGraphT > Class Template Reference

Manages the actual routing graph and provieds different views on the edges (lazily computed) More...

#include <Forward.h>

Public Types

using CostFilter = EdgeCostFilter< BaseGraphT >
 
using Edge = typename boost::graph_traits< BaseGraphT >::edge_descriptor
 
using FilteredGraph = FilteredGraphT< BaseGraphT >
 
using Vertex = typename boost::graph_traits< BaseGraphT >::vertex_descriptor
 

Public Member Functions

void addEdge (const ConstLaneletOrArea &from, const ConstLaneletOrArea &to, const EdgeInfo &edgeInfo)
 
void addEdge (Vertex from, Vertex to, const EdgeInfo &edgeInfo)
 
Vertex addVertex (const typename BaseGraphT::vertex_property_type &property)
 add new lanelet to graph More...
 
FilteredGraph adjacentLeft (RoutingCostId routingCostId=0) const
 
FilteredGraph adjacentRight (RoutingCostId routingCostId=0) const
 
FilteredGraph conflicting (RoutingCostId routingCostId=0) const
 
bool empty () const noexcept
 
const BaseGraphT & get () const noexcept
 
BaseGraphT & get () noexcept
 
Optional< EdgeInfogetEdgeInfo (const ConstLanelet &from, const ConstLanelet &to) const noexcept
 Received the edgeInfo between two given vertices. More...
 
template<typename Graph >
Optional< EdgeInfogetEdgeInfoFor (const ConstLanelet &from, const ConstLanelet &to, const Graph &g) const noexcept
 Received the edgeInfo between two given vertices and a given (filtered)graph. More...
 
Optional< typename boost::graph_traits< BaseGraphT >::vertex_descriptor > getVertex (const ConstLaneletOrArea &lanelet) const noexcept
 Helper function to determine the graph vertex of a given lanelet. More...
 
 Graph (size_t numRoutingCosts)
 
FilteredGraph left (RoutingCostId routingCostId=0) const
 
size_t numRoutingCosts () const noexcept
 
FilteredGraph right (RoutingCostId routingCostId=0) const
 
FilteredGraph somehowLeft (RoutingCostId routingCostId=0) const
 
FilteredGraph somehowRight (RoutingCostId routingCostId=0) const
 
const LaneletOrAreaToVertexvertexLookup () const noexcept
 
FilteredGraph withAreasAndLaneChanges (RoutingCostId routingCostId=0) const
 
FilteredGraph withAreasWithoutLaneChanges (RoutingCostId routingCostId=0) const
 
FilteredGraph withLaneChanges (RoutingCostId routingCostId=0) const
 
FilteredGraph withoutConflicting (RoutingCostId routingCostId=0) const
 
FilteredGraph withoutLaneChanges (RoutingCostId routingCostId=0) const
 

Private Member Functions

FilteredGraph getFilteredGraph (RoutingCostId routingCostId, RelationType relations) const
 

Private Attributes

BaseGraphT graph_
 The actual graph object. More...
 
LaneletOrAreaToVertex laneletOrAreaToVertex_
 Mapping of lanelets/areas to vertices of the graph. More...
 
size_t numRoutingCosts_
 Number of available routing cost calculation methods. More...
 

Detailed Description

template<typename BaseGraphT>
class lanelet::routing::internal::Graph< BaseGraphT >

Manages the actual routing graph and provieds different views on the edges (lazily computed)

Definition at line 17 of file Forward.h.

Member Typedef Documentation

◆ CostFilter

template<typename BaseGraphT >
using lanelet::routing::internal::Graph< BaseGraphT >::CostFilter = EdgeCostFilter<BaseGraphT>

Definition at line 110 of file Graph.h.

◆ Edge

template<typename BaseGraphT >
using lanelet::routing::internal::Graph< BaseGraphT >::Edge = typename boost::graph_traits<BaseGraphT>::edge_descriptor

Definition at line 112 of file Graph.h.

◆ FilteredGraph

template<typename BaseGraphT >
using lanelet::routing::internal::Graph< BaseGraphT >::FilteredGraph = FilteredGraphT<BaseGraphT>

Definition at line 109 of file Graph.h.

◆ Vertex

template<typename BaseGraphT >
using lanelet::routing::internal::Graph< BaseGraphT >::Vertex = typename boost::graph_traits<BaseGraphT>::vertex_descriptor

Definition at line 111 of file Graph.h.

Constructor & Destructor Documentation

◆ Graph()

template<typename BaseGraphT >
lanelet::routing::internal::Graph< BaseGraphT >::Graph ( size_t  numRoutingCosts)
inlineexplicit

Definition at line 114 of file Graph.h.

Member Function Documentation

◆ addEdge() [1/2]

template<typename BaseGraphT >
void lanelet::routing::internal::Graph< BaseGraphT >::addEdge ( const ConstLaneletOrArea from,
const ConstLaneletOrArea to,
const EdgeInfo edgeInfo 
)
inline

Definition at line 179 of file Graph.h.

◆ addEdge() [2/2]

template<typename BaseGraphT >
void lanelet::routing::internal::Graph< BaseGraphT >::addEdge ( Vertex  from,
Vertex  to,
const EdgeInfo edgeInfo 
)
inline

Definition at line 189 of file Graph.h.

◆ addVertex()

template<typename BaseGraphT >
Vertex lanelet::routing::internal::Graph< BaseGraphT >::addVertex ( const typename BaseGraphT::vertex_property_type &  property)
inline

add new lanelet to graph

Definition at line 171 of file Graph.h.

◆ adjacentLeft()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::adjacentLeft ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 152 of file Graph.h.

◆ adjacentRight()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::adjacentRight ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 156 of file Graph.h.

◆ conflicting()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::conflicting ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 160 of file Graph.h.

◆ empty()

template<typename BaseGraphT >
bool lanelet::routing::internal::Graph< BaseGraphT >::empty ( ) const
inlinenoexcept

Definition at line 168 of file Graph.h.

◆ get() [1/2]

template<typename BaseGraphT >
const BaseGraphT& lanelet::routing::internal::Graph< BaseGraphT >::get ( ) const
inlinenoexcept

Definition at line 116 of file Graph.h.

◆ get() [2/2]

template<typename BaseGraphT >
BaseGraphT& lanelet::routing::internal::Graph< BaseGraphT >::get ( )
inlinenoexcept

Definition at line 117 of file Graph.h.

◆ getEdgeInfo()

template<typename BaseGraphT >
Optional<EdgeInfo> lanelet::routing::internal::Graph< BaseGraphT >::getEdgeInfo ( const ConstLanelet from,
const ConstLanelet to 
) const
inlinenoexcept

Received the edgeInfo between two given vertices.

Returns
EdgeInfo or nothing if there's no edge

Definition at line 203 of file Graph.h.

◆ getEdgeInfoFor()

template<typename BaseGraphT >
template<typename Graph >
Optional<EdgeInfo> lanelet::routing::internal::Graph< BaseGraphT >::getEdgeInfoFor ( const ConstLanelet from,
const ConstLanelet to,
const Graph< BaseGraphT > &  g 
) const
inlinenoexcept

Received the edgeInfo between two given vertices and a given (filtered)graph.

Returns
EdgeInfo or nothing if there's no edge

Definition at line 210 of file Graph.h.

◆ getFilteredGraph()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::getFilteredGraph ( RoutingCostId  routingCostId,
RelationType  relations 
) const
inlineprivate

Definition at line 234 of file Graph.h.

◆ getVertex()

template<typename BaseGraphT >
Optional<typename boost::graph_traits<BaseGraphT>::vertex_descriptor> lanelet::routing::internal::Graph< BaseGraphT >::getVertex ( const ConstLaneletOrArea lanelet) const
inlinenoexcept

Helper function to determine the graph vertex of a given lanelet.

Definition at line 224 of file Graph.h.

◆ left()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::left ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 138 of file Graph.h.

◆ numRoutingCosts()

template<typename BaseGraphT >
size_t lanelet::routing::internal::Graph< BaseGraphT >::numRoutingCosts ( ) const
inlinenoexcept

Definition at line 118 of file Graph.h.

◆ right()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::right ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 145 of file Graph.h.

◆ somehowLeft()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::somehowLeft ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 141 of file Graph.h.

◆ somehowRight()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::somehowRight ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 148 of file Graph.h.

◆ vertexLookup()

template<typename BaseGraphT >
const LaneletOrAreaToVertex& lanelet::routing::internal::Graph< BaseGraphT >::vertexLookup ( ) const
inlinenoexcept

Definition at line 119 of file Graph.h.

◆ withAreasAndLaneChanges()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::withAreasAndLaneChanges ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 129 of file Graph.h.

◆ withAreasWithoutLaneChanges()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::withAreasWithoutLaneChanges ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 134 of file Graph.h.

◆ withLaneChanges()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::withLaneChanges ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 121 of file Graph.h.

◆ withoutConflicting()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::withoutConflicting ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 164 of file Graph.h.

◆ withoutLaneChanges()

template<typename BaseGraphT >
FilteredGraph lanelet::routing::internal::Graph< BaseGraphT >::withoutLaneChanges ( RoutingCostId  routingCostId = 0) const
inline

Definition at line 125 of file Graph.h.

Member Data Documentation

◆ graph_

template<typename BaseGraphT >
BaseGraphT lanelet::routing::internal::Graph< BaseGraphT >::graph_
private

The actual graph object.

Definition at line 240 of file Graph.h.

◆ laneletOrAreaToVertex_

template<typename BaseGraphT >
LaneletOrAreaToVertex lanelet::routing::internal::Graph< BaseGraphT >::laneletOrAreaToVertex_
private

Mapping of lanelets/areas to vertices of the graph.

Definition at line 241 of file Graph.h.

◆ numRoutingCosts_

template<typename BaseGraphT >
size_t lanelet::routing::internal::Graph< BaseGraphT >::numRoutingCosts_
private

Number of available routing cost calculation methods.

Definition at line 242 of file Graph.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