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< LaneletVertexId > | getAllNeighbourLanelets (LaneletVertexId ofVertex, const Graph &ofRoute) |
template<RelationType R, typename Graph > | |
Optional< LaneletVertexId > | getNext (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) |
using lanelet::routing::internal::ConflictOrAdjacentToRouteGraph = typedef boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter> |
Definition at line 395 of file GraphUtils.h.
using lanelet::routing::internal::ConflictsWithPathGraph = typedef boost::filtered_graph<OriginalGraph, NoConflictingFilter, OnRouteAndConflictFilter> |
Definition at line 396 of file GraphUtils.h.
using lanelet::routing::internal::DijkstraSearchMap = typedef std::map<VertexT, VertexState> |
Definition at line 33 of file ShortestPath.h.
using lanelet::routing::internal::DrivableGraph = typedef boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter> |
Definition at line 390 of file GraphUtils.h.
using lanelet::routing::internal::FilteredGraphDesc = typedef std::pair<size_t, RelationType> |
using lanelet::routing::internal::FilteredGraphT = typedef boost::filtered_graph<BaseGraphT, EdgeCostFilter<BaseGraphT> > |
using lanelet::routing::internal::FilteredGraphTraits = typedef boost::graph_traits<FilteredGraphT<BaseGraphT> > |
using lanelet::routing::internal::FilteredRouteGraph = typedef FilteredGraphT<RouteGraphType> |
using lanelet::routing::internal::FilteredRoutingGraph = typedef FilteredGraphT<GraphType> |
using lanelet::routing::internal::GraphTraits = typedef boost::graph_traits<GraphType> |
using lanelet::routing::internal::GraphType = typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo> |
using lanelet::routing::internal::IdPair = typedef std::pair<Id, Id> |
using lanelet::routing::internal::LaneletOrAreaToVertex = typedef std::unordered_map<ConstLaneletOrArea, std::uint32_t> |
using lanelet::routing::internal::LaneletVertexId = typedef GraphTraits::vertex_descriptor |
Definition at line 12 of file GraphUtils.h.
using lanelet::routing::internal::LaneletVertexIds = typedef std::vector<LaneletVertexId> |
Definition at line 13 of file GraphUtils.h.
using lanelet::routing::internal::NextToRouteGraph = typedef boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter> |
Definition at line 393 of file GraphUtils.h.
using lanelet::routing::internal::NoConflictingGraph = typedef boost::filtered_graph<OriginalGraph, NoConflictingFilter> |
Definition at line 391 of file GraphUtils.h.
using lanelet::routing::internal::OnlyConflictingFilter = typedef EdgeRelationFilter<RelationType::Conflicting, OriginalGraph> |
Definition at line 160 of file GraphUtils.h.
using lanelet::routing::internal::OnlyConflictingGraph = typedef boost::filtered_graph<OriginalGraph, OnlyConflictingFilter> |
Definition at line 392 of file GraphUtils.h.
using lanelet::routing::internal::OnlyDrivableEdgesFilter = typedef EdgeRelationFilter<RelationType::Successor | RelationType::Left | RelationType::Right, OriginalGraph> |
Removes edges from the graph that are not drivable (e.g. adjacent or conflicing)
Definition at line 159 of file GraphUtils.h.
using lanelet::routing::internal::OnRouteGraph = typedef boost::filtered_graph<OriginalGraph, boost::keep_all, OnRouteFilter> |
Definition at line 389 of file GraphUtils.h.
using lanelet::routing::internal::OriginalGraph = typedef boost::filtered_graph<GraphType, OriginalGraphFilter> |
Definition at line 129 of file GraphUtils.h.
using lanelet::routing::internal::RouteGraphType = typedef boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo> |
using lanelet::routing::internal::RouteLanelets = typedef std::set<LaneletVertexId> |
Definition at line 14 of file GraphUtils.h.
bool lanelet::routing::internal::anySidewayNeighbourIs | ( | Vertex | v, |
const Graph & | g, | ||
Func && | f | ||
) |
Definition at line 77 of file GraphUtils.h.
|
inline |
GraphML export function.
filename | Fully qualified file name - ideally with extension (.graphml) |
g | Graph to export |
relationTypes | Relations that will be included in the export |
routingCostId | ID of the routing cost module |
Definition at line 126 of file RoutingGraphVisualization.h.
|
inline |
Implementation of graphML export function.
filename | Fully qualified file name - ideally with extension (.graphml) |
g | Graph to export |
eFilter | Edge filter that will be used to create a filtered graph |
vFilter | Vertex filter. Not used yet |
Definition at line 98 of file RoutingGraphVisualization.h.
|
inline |
GraphViz export function.
filename | Fully qualified file name - ideally with extension (.gv) |
g | Graph to export |
relationTypes | Relations that will be included in the export |
routingCostId | ID of the routing cost module |
Definition at line 86 of file RoutingGraphVisualization.h.
|
inline |
Implementation of graphViz export function.
filename | Fully qualified file name - ideally with extension (.gv) |
g | Graph to export |
edgeFilter | Edge filter that will be used to create a filtered graph |
vertexFilter | Vertex filter. Not used yet |
Definition at line 64 of file RoutingGraphVisualization.h.
|
inline |
Definition at line 45 of file ShortestPath.h.
|
inline |
Definition at line 304 of file GraphUtils.h.
std::set<LaneletVertexId> lanelet::routing::internal::getAllNeighbourLanelets | ( | LaneletVertexId | ofVertex, |
const Graph & | ofRoute | ||
) |
Definition at line 93 of file GraphUtils.h.
Optional<LaneletVertexId> lanelet::routing::internal::getNext | ( | LaneletVertexId | ofVertex, |
const Graph & | g | ||
) |
Definition at line 29 of file GraphUtils.h.
|
inline |
Definition at line 17 of file GraphUtils.h.
|
inline |
Definition at line 21 of file GraphUtils.h.
|
inline |
Definition at line 25 of file GraphUtils.h.
|
inline |
Definition at line 54 of file ShortestPath.h.
|
inline |
Definition at line 312 of file GraphUtils.h.