Classes | Typedefs | Functions
lanelet::routing::internal Namespace Reference

Classes

class  ConflictingSectionFilter
 Finds vertices that are in conflict or adjacent to some vertices (not reachable though bidirectional lane changes) More...
 
class  ConnectedPathIterator
 An iterator that finds paths from a start vertex to all reachable destinations. More...
 
struct  DijkstraCostMap
 
class  DijkstraStyleSearch
 
struct  EdgeCostFilter
 An internal edge filter to get a filtered view on the graph. More...
 
struct  EdgeInfo
 Internal information of an edge in the graph. More...
 
class  EdgeRelationFilter
 
class  EdgeWriterGraphViz
 Internal edge writer for graphViz file export. Includes label, color and if existent routing cost (as 'weight') and the routing cost module ID. More...
 
struct  GetEdges
 
struct  GetEdges< false >
 
struct  GetEdges< true >
 
struct  GetTarget
 
struct  GetTarget< false >
 
struct  GetTarget< true >
 
class  Graph
 Manages the actual routing graph and provieds different views on the edges (lazily computed) More...
 
class  LaneChangeLaneletsCollector
 This class collects lane changable lanelets and combines them to a sequence of adjacent lanechangable lanelets. More...
 
class  NextToRouteFilter
 Removes vertices from the graph that are not adjacent to a set of vertices. Adjacent can also mean conflicting! More...
 
class  NoConflictingFilter
 Removes conflicting edges from the graph. More...
 
class  OnlyDrivableEdgesWithinFilter
 Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) OR leave the route at its end. More...
 
class  OnRouteAndConflictFilter
 Finds vertices within a set of vertices that are in conflict with another set of vertices. More...
 
class  OnRouteFilter
 Reduces the graph to a set of desired vertices. More...
 
class  OriginalGraphFilter
 Filter that reduces the original graph by edges that belong to different cost types or lane changes. More...
 
class  RouteBuilder
 Builder class to create a route from a routing graph and the shortest path. More...
 
class  RouteGraph
 
struct  RouteVertexInfo
 Internal information of a vertex in the route graph. More...
 
class  RoutingGraphBuilder
 
class  RoutingGraphGraph
 
struct  SparseColorMap
 For graph queries, we implement our own color map because boost's color does not perform well on sparse graphs. More...
 
struct  VertexInfo
 Internal information of a vertex in the graph If A* search is adapted, this could hold information about longitude and latitude. More...
 
struct  VertexState
 
struct  VertexVisitInformation
 This object carries the required information for the graph neighbourhood search. More...
 
class  VertexWriterGraphViz
 Internal vertex writer for graphViz file export. More...
 

Typedefs

using ConflictOrAdjacentToRouteGraph = boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter >
 
using ConflictsWithPathGraph = boost::filtered_graph< OriginalGraph, NoConflictingFilter, OnRouteAndConflictFilter >
 
template<typename VertexT >
using DijkstraSearchMap = std::map< VertexT, VertexState >
 
using DrivableGraph = boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter >
 
using FilteredGraphDesc = std::pair< size_t, RelationType >
 
template<typename BaseGraphT >
using FilteredGraphT = boost::filtered_graph< BaseGraphT, EdgeCostFilter< BaseGraphT > >
 
template<typename BaseGraphT >
using FilteredGraphTraits = boost::graph_traits< FilteredGraphT< BaseGraphT > >
 
using FilteredRouteGraph = FilteredGraphT< RouteGraphType >
 
using FilteredRoutingGraph = FilteredGraphT< GraphType >
 
using GraphTraits = boost::graph_traits< GraphType >
 
using GraphType = boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo >
 General graph type definitions. More...
 
using IdPair = std::pair< Id, Id >
 
using LaneletOrAreaToVertex = std::unordered_map< ConstLaneletOrArea, std::uint32_t >
 
using LaneletVertexId = GraphTraits::vertex_descriptor
 
using LaneletVertexIds = std::vector< LaneletVertexId >
 
using NextToRouteGraph = boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter >
 
using NoConflictingGraph = boost::filtered_graph< OriginalGraph, NoConflictingFilter >
 
using OnlyConflictingFilter = EdgeRelationFilter< RelationType::Conflicting, OriginalGraph >
 
using OnlyConflictingGraph = boost::filtered_graph< OriginalGraph, OnlyConflictingFilter >
 
using OnlyDrivableEdgesFilter = EdgeRelationFilter< RelationType::Successor|RelationType::Left|RelationType::Right, OriginalGraph >
 Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) More...
 
using OnRouteGraph = boost::filtered_graph< OriginalGraph, boost::keep_all, OnRouteFilter >
 
using OriginalGraph = boost::filtered_graph< GraphType, OriginalGraphFilter >
 
using RouteGraphType = boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo >
 
using RouteLanelets = std::set< LaneletVertexId >
 

Functions

template<typename Vertex , typename Graph , typename Func >
bool anySidewayNeighbourIs (Vertex v, const Graph &g, Func &&f)
 
template<typename G >
void exportGraphMLImpl (const std::string &filename, const G &g, const RelationType &relationTypes, RoutingCostId routingCostId=0)
 GraphML export function. More...
 
template<typename G , typename E = boost::keep_all, typename V = boost::keep_all>
void exportGraphMLImpl (const std::string &filename, const G &g, E eFilter=boost::keep_all(), V vFilter=boost::keep_all())
 Implementation of graphML export function. More...
 
template<typename G >
void exportGraphVizImpl (const std::string &filename, const G &g, const RelationType &relationTypes, RoutingCostId routingCostId=0)
 GraphViz export function. More...
 
template<typename G , typename E = boost::keep_all, typename V = boost::keep_all>
void exportGraphVizImpl (const std::string &filename, const G &g, E edgeFilter=boost::keep_all(), V vertexFilter=boost::keep_all())
 Implementation of graphViz export function. More...
 
template<typename VertexT >
DijkstraCostMap< VertexT >::value_type get (const DijkstraCostMap< VertexT > &map, VertexT key)
 
SparseColorMap::value_type get (const SparseColorMap &map, LaneletVertexId key)
 
template<typename Graph >
std::set< LaneletVertexIdgetAllNeighbourLanelets (LaneletVertexId ofVertex, const Graph &ofRoute)
 
template<RelationType R, typename Graph >
Optional< LaneletVertexIdgetNext (LaneletVertexId ofVertex, const Graph &g)
 
template<typename ContainerT , typename T >
bool has (const ContainerT &c, const T &t)
 
template<typename ContainerT , typename T >
bool has (const std::set< T > &c, const T &t)
 
template<RelationType R, typename GraphT , typename EdgeT >
bool hasRelation (const GraphT &g, EdgeT e)
 
template<typename VertexT >
void put (DijkstraCostMap< VertexT > &map, VertexT key, typename DijkstraCostMap< VertexT >::value_type value)
 
void put (SparseColorMap &map, LaneletVertexId key, SparseColorMap::value_type value)
 

Typedef Documentation

◆ ConflictOrAdjacentToRouteGraph

Definition at line 395 of file GraphUtils.h.

◆ ConflictsWithPathGraph

Definition at line 396 of file GraphUtils.h.

◆ DijkstraSearchMap

template<typename VertexT >
using lanelet::routing::internal::DijkstraSearchMap = typedef std::map<VertexT, VertexState>

Definition at line 33 of file ShortestPath.h.

◆ DrivableGraph

Definition at line 390 of file GraphUtils.h.

◆ FilteredGraphDesc

using lanelet::routing::internal::FilteredGraphDesc = typedef std::pair<size_t, RelationType>

Definition at line 103 of file Graph.h.

◆ FilteredGraphT

template<typename BaseGraphT >
using lanelet::routing::internal::FilteredGraphT = typedef boost::filtered_graph<BaseGraphT, EdgeCostFilter<BaseGraphT> >

Filtered graphs provide a filtered view on a graph. Here we can filter out types of relations (e.g. CONFLICTING) or filter by routing cost module ID.

Definition at line 54 of file Graph.h.

◆ FilteredGraphTraits

template<typename BaseGraphT >
using lanelet::routing::internal::FilteredGraphTraits = typedef boost::graph_traits<FilteredGraphT<BaseGraphT> >

Definition at line 57 of file Graph.h.

◆ FilteredRouteGraph

Definition at line 60 of file Graph.h.

◆ FilteredRoutingGraph

Definition at line 59 of file Graph.h.

◆ GraphTraits

using lanelet::routing::internal::GraphTraits = typedef boost::graph_traits<GraphType>

Definition at line 46 of file Graph.h.

◆ GraphType

using lanelet::routing::internal::GraphType = typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo>

General graph type definitions.

Definition at line 43 of file Graph.h.

◆ IdPair

using lanelet::routing::internal::IdPair = typedef std::pair<Id, Id>

Definition at line 14 of file Forward.h.

◆ LaneletOrAreaToVertex

using lanelet::routing::internal::LaneletOrAreaToVertex = typedef std::unordered_map<ConstLaneletOrArea, std::uint32_t>

Definition at line 102 of file Graph.h.

◆ LaneletVertexId

using lanelet::routing::internal::LaneletVertexId = typedef GraphTraits::vertex_descriptor

Definition at line 12 of file GraphUtils.h.

◆ LaneletVertexIds

Definition at line 13 of file GraphUtils.h.

◆ NextToRouteGraph

Definition at line 393 of file GraphUtils.h.

◆ NoConflictingGraph

Definition at line 391 of file GraphUtils.h.

◆ OnlyConflictingFilter

Definition at line 160 of file GraphUtils.h.

◆ OnlyConflictingGraph

Definition at line 392 of file GraphUtils.h.

◆ OnlyDrivableEdgesFilter

Removes edges from the graph that are not drivable (e.g. adjacent or conflicing)

Definition at line 159 of file GraphUtils.h.

◆ OnRouteGraph

using lanelet::routing::internal::OnRouteGraph = typedef boost::filtered_graph<OriginalGraph, boost::keep_all, OnRouteFilter>

Definition at line 389 of file GraphUtils.h.

◆ OriginalGraph

Definition at line 129 of file GraphUtils.h.

◆ RouteGraphType

using lanelet::routing::internal::RouteGraphType = typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo>

Definition at line 45 of file Graph.h.

◆ RouteLanelets

Definition at line 14 of file GraphUtils.h.

Function Documentation

◆ anySidewayNeighbourIs()

template<typename Vertex , typename Graph , typename Func >
bool lanelet::routing::internal::anySidewayNeighbourIs ( Vertex  v,
const Graph g,
Func &&  f 
)

Definition at line 77 of file GraphUtils.h.

◆ exportGraphMLImpl() [1/2]

template<typename G >
void lanelet::routing::internal::exportGraphMLImpl ( const std::string &  filename,
const G &  g,
const RelationType relationTypes,
RoutingCostId  routingCostId = 0 
)
inline

GraphML export function.

Parameters
filenameFully qualified file name - ideally with extension (.graphml)
gGraph to export
relationTypesRelations that will be included in the export
routingCostIdID of the routing cost module

Definition at line 126 of file RoutingGraphVisualization.h.

◆ exportGraphMLImpl() [2/2]

template<typename G , typename E = boost::keep_all, typename V = boost::keep_all>
void lanelet::routing::internal::exportGraphMLImpl ( const std::string &  filename,
const G &  g,
eFilter = boost::keep_all(),
vFilter = boost::keep_all() 
)
inline

Implementation of graphML export function.

Parameters
filenameFully qualified file name - ideally with extension (.graphml)
gGraph to export
eFilterEdge filter that will be used to create a filtered graph
vFilterVertex filter. Not used yet

Definition at line 98 of file RoutingGraphVisualization.h.

◆ exportGraphVizImpl() [1/2]

template<typename G >
void lanelet::routing::internal::exportGraphVizImpl ( const std::string &  filename,
const G &  g,
const RelationType relationTypes,
RoutingCostId  routingCostId = 0 
)
inline

GraphViz export function.

Parameters
filenameFully qualified file name - ideally with extension (.gv)
gGraph to export
relationTypesRelations that will be included in the export
routingCostIdID of the routing cost module

Definition at line 86 of file RoutingGraphVisualization.h.

◆ exportGraphVizImpl() [2/2]

template<typename G , typename E = boost::keep_all, typename V = boost::keep_all>
void lanelet::routing::internal::exportGraphVizImpl ( const std::string &  filename,
const G &  g,
edgeFilter = boost::keep_all(),
vertexFilter = boost::keep_all() 
)
inline

Implementation of graphViz export function.

Parameters
filenameFully qualified file name - ideally with extension (.gv)
gGraph to export
edgeFilterEdge filter that will be used to create a filtered graph
vertexFilterVertex filter. Not used yet

Definition at line 64 of file RoutingGraphVisualization.h.

◆ get() [1/2]

template<typename VertexT >
DijkstraCostMap<VertexT>::value_type lanelet::routing::internal::get ( const DijkstraCostMap< VertexT > &  map,
VertexT  key 
)
inline

Definition at line 45 of file ShortestPath.h.

◆ get() [2/2]

SparseColorMap::value_type lanelet::routing::internal::get ( const SparseColorMap map,
LaneletVertexId  key 
)
inline

Definition at line 304 of file GraphUtils.h.

◆ getAllNeighbourLanelets()

template<typename Graph >
std::set<LaneletVertexId> lanelet::routing::internal::getAllNeighbourLanelets ( LaneletVertexId  ofVertex,
const Graph ofRoute 
)

Definition at line 93 of file GraphUtils.h.

◆ getNext()

template<RelationType R, typename Graph >
Optional<LaneletVertexId> lanelet::routing::internal::getNext ( LaneletVertexId  ofVertex,
const Graph g 
)

Definition at line 29 of file GraphUtils.h.

◆ has() [1/2]

template<typename ContainerT , typename T >
bool lanelet::routing::internal::has ( const ContainerT &  c,
const T &  t 
)
inline

Definition at line 17 of file GraphUtils.h.

◆ has() [2/2]

template<typename ContainerT , typename T >
bool lanelet::routing::internal::has ( const std::set< T > &  c,
const T &  t 
)
inline

Definition at line 21 of file GraphUtils.h.

◆ hasRelation()

template<RelationType R, typename GraphT , typename EdgeT >
bool lanelet::routing::internal::hasRelation ( const GraphT &  g,
EdgeT  e 
)
inline

Definition at line 25 of file GraphUtils.h.

◆ put() [1/2]

template<typename VertexT >
void lanelet::routing::internal::put ( DijkstraCostMap< VertexT > &  map,
VertexT  key,
typename DijkstraCostMap< VertexT >::value_type  value 
)
inline

Definition at line 54 of file ShortestPath.h.

◆ put() [2/2]

void lanelet::routing::internal::put ( SparseColorMap map,
LaneletVertexId  key,
SparseColorMap::value_type  value 
)
inline

Definition at line 312 of file GraphUtils.h.



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