#include <lanelet2_core/utility/Optional.h>
#include <boost/graph/depth_first_search.hpp>
#include <boost/graph/two_bit_color_map.hpp>
#include "lanelet2_routing/internal/Graph.h"
Go to the source code of this file.
Classes | |
class | lanelet::routing::internal::ConflictingSectionFilter |
Finds vertices that are in conflict or adjacent to some vertices (not reachable though bidirectional lane changes) More... | |
class | lanelet::routing::internal::ConnectedPathIterator< GraphT > |
An iterator that finds paths from a start vertex to all reachable destinations. More... | |
class | lanelet::routing::internal::EdgeRelationFilter< Relation, GraphType > |
struct | lanelet::routing::internal::GetEdges< Backwards > |
struct | lanelet::routing::internal::GetEdges< false > |
struct | lanelet::routing::internal::GetEdges< true > |
struct | lanelet::routing::internal::GetTarget< Backwards > |
struct | lanelet::routing::internal::GetTarget< false > |
struct | lanelet::routing::internal::GetTarget< true > |
class | lanelet::routing::internal::NextToRouteFilter |
Removes vertices from the graph that are not adjacent to a set of vertices. Adjacent can also mean conflicting! More... | |
class | lanelet::routing::internal::NoConflictingFilter |
Removes conflicting edges from the graph. More... | |
class | lanelet::routing::internal::OnlyDrivableEdgesWithinFilter |
Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) OR leave the route at its end. More... | |
class | lanelet::routing::internal::OnRouteAndConflictFilter |
Finds vertices within a set of vertices that are in conflict with another set of vertices. More... | |
class | lanelet::routing::internal::OnRouteFilter |
Reduces the graph to a set of desired vertices. More... | |
class | lanelet::routing::internal::OriginalGraphFilter |
Filter that reduces the original graph by edges that belong to different cost types or lane changes. More... | |
class | lanelet::routing::internal::ConnectedPathIterator< GraphT >::PathVisitor< Func > |
struct | lanelet::routing::internal::SparseColorMap |
For graph queries, we implement our own color map because boost's color does not perform well on sparse graphs. More... | |
Namespaces | |
lanelet | |
lanelet::routing | |
lanelet::routing::internal | |
Typedefs | |
using | lanelet::routing::internal::ConflictOrAdjacentToRouteGraph = boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter > |
using | lanelet::routing::internal::ConflictsWithPathGraph = boost::filtered_graph< OriginalGraph, NoConflictingFilter, OnRouteAndConflictFilter > |
using | lanelet::routing::internal::DrivableGraph = boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter > |
using | lanelet::routing::internal::LaneletVertexId = GraphTraits::vertex_descriptor |
using | lanelet::routing::internal::LaneletVertexIds = std::vector< LaneletVertexId > |
using | lanelet::routing::internal::NextToRouteGraph = boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter > |
using | lanelet::routing::internal::NoConflictingGraph = boost::filtered_graph< OriginalGraph, NoConflictingFilter > |
using | lanelet::routing::internal::OnlyConflictingFilter = EdgeRelationFilter< RelationType::Conflicting, OriginalGraph > |
using | lanelet::routing::internal::OnlyConflictingGraph = boost::filtered_graph< OriginalGraph, OnlyConflictingFilter > |
using | lanelet::routing::internal::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 | lanelet::routing::internal::OnRouteGraph = boost::filtered_graph< OriginalGraph, boost::keep_all, OnRouteFilter > |
using | lanelet::routing::internal::OriginalGraph = boost::filtered_graph< GraphType, OriginalGraphFilter > |
using | lanelet::routing::internal::RouteLanelets = std::set< LaneletVertexId > |
Functions | |
template<typename Vertex , typename Graph , typename Func > | |
bool | lanelet::routing::internal::anySidewayNeighbourIs (Vertex v, const Graph &g, Func &&f) |
SparseColorMap::value_type | lanelet::routing::internal::get (const SparseColorMap &map, LaneletVertexId key) |
template<typename Graph > | |
std::set< LaneletVertexId > | lanelet::routing::internal::getAllNeighbourLanelets (LaneletVertexId ofVertex, const Graph &ofRoute) |
template<RelationType R, typename Graph > | |
Optional< LaneletVertexId > | lanelet::routing::internal::getNext (LaneletVertexId ofVertex, const Graph &g) |
template<typename ContainerT , typename T > | |
bool | lanelet::routing::internal::has (const ContainerT &c, const T &t) |
template<typename ContainerT , typename T > | |
bool | lanelet::routing::internal::has (const std::set< T > &c, const T &t) |
template<RelationType R, typename GraphT , typename EdgeT > | |
bool | lanelet::routing::internal::hasRelation (const GraphT &g, EdgeT e) |
void | lanelet::routing::internal::put (SparseColorMap &map, LaneletVertexId key, SparseColorMap::value_type value) |