Go to the documentation of this file.
5 #include <boost/graph/adjacency_list.hpp>
6 #include <boost/graph/filtered_graph.hpp>
43 using GraphType = boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo>;
45 boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo>;
48 template <
typename BaseGraphT>
53 template <
typename BaseGraphT>
54 using FilteredGraphT = boost::filtered_graph<BaseGraphT, EdgeCostFilter<BaseGraphT>>;
56 template <
typename BaseGraphT>
63 template <
typename GraphT>
87 template <
typename Edge>
96 typename boost::property_map<const GraphT, RelationType EdgeInfo::*>::const_type
98 typename boost::property_map<const GraphT, RoutingCostId EdgeInfo::*>::const_type
106 template <
typename BaseGraphT>
111 using Vertex =
typename boost::graph_traits<BaseGraphT>::vertex_descriptor;
112 using Edge =
typename boost::graph_traits<BaseGraphT>::edge_descriptor;
116 inline const BaseGraphT&
get() const noexcept {
return graph_; }
172 GraphType::vertex_descriptor vd = 0;
173 vd = boost::add_vertex(
graph_);
182 if (!fromVertex || !toVertex) {
183 assert(
false &&
"Lanelet/Area is not part of the graph.");
186 addEdge(*fromVertex, *toVertex, edgeInfo);
196 auto edge = boost::add_edge(from, to,
graph_);
197 assert(edge.second &&
"Edge could not be added to the graph.");
198 graph_[edge.first] = edgeInfo;
209 template <
typename Graph>
213 if (!fromVertex || !toVertex) {
216 auto edgeToNext{boost::edge(*fromVertex, *toVertex, g)};
217 if (edgeToNext.second) {
218 return g[edgeToNext.first];
228 }
catch (std::out_of_range&) {
236 throw InvalidInputError(
"Routing Cost ID is higher than the number of routing modules.");
RoutingCostId routingCostId_
Id of the routing cost functor to use.
bool empty() const noexcept
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
FilteredGraph withoutConflicting(RoutingCostId routingCostId=0) const
FilteredGraphT< GraphType > FilteredGraph
RelationType relations_
Relations that pass the filter.
size_t numRoutingCosts_
Number of available routing cost calculation methods.
FilteredGraph withLaneChanges(RoutingCostId routingCostId=0) const
const ConstLaneletOrArea & get() const
double routingCost
Calculcated routing cost. Infinity if not routable.
void addEdge(const ConstLaneletOrArea &from, const ConstLaneletOrArea &to, const EdgeInfo &edgeInfo)
An internal edge filter to get a filtered view on the graph.
FilteredGraphT< RouteGraphType > FilteredRouteGraph
boost::filtered_graph< BaseGraphT, EdgeCostFilter< BaseGraphT > > FilteredGraphT
EdgeCostFilter(const GraphT &graph, RoutingCostId routingCostId)
Constructor for a filter that includes all relation types.
FilteredGraph withAreasWithoutLaneChanges(RoutingCostId routingCostId=0) const
EdgeCostFilter< BaseGraphT > CostFilter
std::pair< size_t, RelationType > FilteredGraphDesc
LaneletOrAreaToVertex laneletOrAreaToVertex_
Mapping of lanelets/areas to vertices of the graph.
bool operator()(const Edge &e) const
Operator that determines wheter an edge should pass the filter or not.
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
ConstLaneletOrAreas conflictingInMap
EdgeCostFilter()=default
Needed to be able to iterate edges.
void addEdge(Vertex from, Vertex to, const EdgeInfo &edgeInfo)
RoutingCostId costId
ID of the routing cost module that was used to calculate cost.
FilteredGraph withAreasAndLaneChanges(RoutingCostId routingCostId=0) const
size_t numRoutingCosts() const noexcept
FilteredGraph adjacentLeft(RoutingCostId routingCostId=0) const
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.
ConstLaneletOrArea laneletOrArea
boost::optional< T > Optional
FilteredGraphT< GraphType > FilteredRoutingGraph
boost::graph_traits< GraphType > GraphTraits
const BaseGraphT & get() const noexcept
Graph(size_t numRoutingCosts)
const LaneletOrAreaToVertex & vertexLookup() const noexcept
SparseColorMap::value_type get(const SparseColorMap &map, LaneletVertexId key)
Internal information of a vertex in the graph If A* search is adapted, this could hold information ab...
typename boost::graph_traits< GraphType >::vertex_descriptor Vertex
FilteredGraph left(RoutingCostId routingCostId=0) const
Optional< EdgeInfo > getEdgeInfo(const ConstLanelet &from, const ConstLanelet &to) const noexcept
Received the edgeInfo between two given vertices.
std::unordered_map< ConstLaneletOrArea, std::uint32_t > LaneletOrAreaToVertex
const ConstLanelet & get() const
@ Conflicting
Unreachable but with overlapping shape.
Manages the actual routing graph and provieds different views on the edges (lazily computed)
FilteredGraph adjacentRight(RoutingCostId routingCostId=0) const
Vertex addVertex(const typename BaseGraphT::vertex_property_type &property)
add new lanelet to graph
Internal information of a vertex in the route graph.
FilteredGraph getFilteredGraph(RoutingCostId routingCostId, RelationType relations) const
@ Left
(the only) directly adjacent, reachable left neighbour
@ AdjacentLeft
directly adjacent, unreachable left neighbor
EdgeCostFilter(const GraphT &graph, RoutingCostId routingCostId, const RelationType &relation)
Constructor for a filter that includes all allowed relations in 'relation'.
boost::property_map< const GraphT, RoutingCostId EdgeInfo::* >::const_type pmIds_
Property map to the routing cost IDs of the edges.
Optional< EdgeInfo > getEdgeInfoFor(const ConstLanelet &from, const ConstLanelet &to, const Graph &g) const noexcept
Received the edgeInfo between two given vertices and a given (filtered)graph.
BaseGraphT graph_
The actual graph object.
Thrown when an there's an error in the routing graph. It will feature further information.
typename boost::graph_traits< GraphType >::edge_descriptor Edge
const ConstArea & area() const
FilteredGraph right(RoutingCostId routingCostId=0) const
@ AdjacentRight
directly adjacent, unreachable right neighbor
BaseGraphT & get() noexcept
RelationType relation
Relation between the two lanelets. E.g. SUCCESSOR or CONFLICTING.
boost::property_map< const GraphT, RelationType EdgeInfo::* >::const_type pmRelation_
Property map to the relations of edges in the graph.
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo > RouteGraphType
boost::graph_traits< FilteredGraphT< BaseGraphT > > FilteredGraphTraits
constexpr RelationType allRelations()
FilteredGraph withoutLaneChanges(RoutingCostId routingCostId=0) const
@ Right
(the only) directly adjacent, reachable right neighbour
FilteredGraph somehowRight(RoutingCostId routingCostId=0) const
FilteredGraph conflicting(RoutingCostId routingCostId=0) const
@ Area
Adjacent to a reachable area.
const ConstLanelet & lanelet() const
FilteredGraph somehowLeft(RoutingCostId routingCostId=0) const
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo > GraphType
General graph type definitions.
Internal information of an edge in the graph.
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49