Graph.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #include <boost/graph/adjacency_list.hpp>
6 #include <boost/graph/filtered_graph.hpp>
7 #include <map>
8 #include <utility>
9 
12 
13 namespace lanelet {
14 namespace routing {
15 namespace internal {
18 struct VertexInfo {
19  // careful. You must be sure that this is indeed a lanelet
20  const ConstLanelet& lanelet() const { return static_cast<const ConstLanelet&>(laneletOrArea); }
21  const ConstArea& area() const { return static_cast<const ConstArea&>(laneletOrArea); }
22  const ConstLaneletOrArea& get() const { return laneletOrArea; }
24 };
25 
28  const ConstLanelet& get() const { return lanelet; }
29 
33 };
34 
36 struct EdgeInfo {
37  double routingCost;
40 };
41 
43 using GraphType = boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo>;
44 using RouteGraphType =
45  boost::adjacency_list<boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo>;
46 using GraphTraits = boost::graph_traits<GraphType>;
47 
48 template <typename BaseGraphT>
50 
53 template <typename BaseGraphT>
54 using FilteredGraphT = boost::filtered_graph<BaseGraphT, EdgeCostFilter<BaseGraphT>>;
55 
56 template <typename BaseGraphT>
57 using FilteredGraphTraits = boost::graph_traits<FilteredGraphT<BaseGraphT>>;
58 
61 
63 template <typename GraphT>
64 struct EdgeCostFilter {
66  EdgeCostFilter() = default;
67 
71  EdgeCostFilter(const GraphT& graph, RoutingCostId routingCostId)
72  : routingCostId_{routingCostId},
75 
80  EdgeCostFilter(const GraphT& graph, RoutingCostId routingCostId, const RelationType& relation)
81  : routingCostId_{routingCostId},
82  relations_{relation},
85 
87  template <typename Edge>
88  inline bool operator()(const Edge& e) const {
89  return boost::get(pmIds_, e) == routingCostId_ &&
91  }
92 
93  private:
96  typename boost::property_map<const GraphT, RelationType EdgeInfo::*>::const_type
98  typename boost::property_map<const GraphT, RoutingCostId EdgeInfo::*>::const_type
100 };
101 
102 using LaneletOrAreaToVertex = std::unordered_map<ConstLaneletOrArea, std::uint32_t>;
103 using FilteredGraphDesc = std::pair<size_t, RelationType>;
104 
106 template <typename BaseGraphT>
107 class Graph {
108  public:
111  using Vertex = typename boost::graph_traits<BaseGraphT>::vertex_descriptor;
112  using Edge = typename boost::graph_traits<BaseGraphT>::edge_descriptor;
113 
115 
116  inline const BaseGraphT& get() const noexcept { return graph_; }
117  inline BaseGraphT& get() noexcept { return graph_; }
118  inline size_t numRoutingCosts() const noexcept { return numRoutingCosts_; }
119  inline const LaneletOrAreaToVertex& vertexLookup() const noexcept { return laneletOrAreaToVertex_; }
120 
121  FilteredGraph withLaneChanges(RoutingCostId routingCostId = 0) const {
123  }
124 
125  FilteredGraph withoutLaneChanges(RoutingCostId routingCostId = 0) const {
126  return getFilteredGraph(routingCostId, RelationType::Successor);
127  }
128 
130  return getFilteredGraph(routingCostId,
132  }
133 
136  }
137 
138  FilteredGraph left(RoutingCostId routingCostId = 0) const {
139  return getFilteredGraph(routingCostId, RelationType::Left);
140  }
141  FilteredGraph somehowLeft(RoutingCostId routingCostId = 0) const {
143  }
144 
145  FilteredGraph right(RoutingCostId routingCostId = 0) const {
146  return getFilteredGraph(routingCostId, RelationType::Right);
147  }
148  FilteredGraph somehowRight(RoutingCostId routingCostId = 0) const {
150  }
151 
152  FilteredGraph adjacentLeft(RoutingCostId routingCostId = 0) const {
153  return getFilteredGraph(routingCostId, RelationType::AdjacentLeft);
154  }
155 
156  FilteredGraph adjacentRight(RoutingCostId routingCostId = 0) const {
157  return getFilteredGraph(routingCostId, RelationType::AdjacentRight);
158  }
159 
160  FilteredGraph conflicting(RoutingCostId routingCostId = 0) const {
161  return getFilteredGraph(routingCostId, RelationType::Conflicting);
162  }
163 
164  FilteredGraph withoutConflicting(RoutingCostId routingCostId = 0) const {
165  return getFilteredGraph(routingCostId, allRelations() | ~RelationType::Conflicting);
166  }
167 
168  inline bool empty() const noexcept { return laneletOrAreaToVertex_.empty(); }
169 
171  inline Vertex addVertex(const typename BaseGraphT::vertex_property_type& property) {
172  GraphType::vertex_descriptor vd = 0;
173  vd = boost::add_vertex(graph_);
174  graph_[vd] = property;
175  laneletOrAreaToVertex_.emplace(property.get(), vd);
176  return vd;
177  }
178 
179  void addEdge(const ConstLaneletOrArea& from, const ConstLaneletOrArea& to, const EdgeInfo& edgeInfo) {
180  auto fromVertex = getVertex(from);
181  auto toVertex = getVertex(to);
182  if (!fromVertex || !toVertex) {
183  assert(false && "Lanelet/Area is not part of the graph."); // NOLINT
184  return;
185  }
186  addEdge(*fromVertex, *toVertex, edgeInfo);
187  }
188 
189  void addEdge(Vertex from, Vertex to, const EdgeInfo& edgeInfo) {
190  if (!std::isfinite(edgeInfo.routingCost)) {
191  return;
192  }
193  if (edgeInfo.routingCost < 0.) {
194  throw RoutingGraphError{"Negative costs calculated by routing cost module!"};
195  }
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;
199  }
200 
203  Optional<EdgeInfo> getEdgeInfo(const ConstLanelet& from, const ConstLanelet& to) const noexcept {
204  return getEdgeInfoFor(from, to, graph_);
205  }
206 
209  template <typename Graph>
210  Optional<EdgeInfo> getEdgeInfoFor(const ConstLanelet& from, const ConstLanelet& to, const Graph& g) const noexcept {
211  auto fromVertex = getVertex(from);
212  auto toVertex = getVertex(to);
213  if (!fromVertex || !toVertex) {
214  return {};
215  }
216  auto edgeToNext{boost::edge(*fromVertex, *toVertex, g)};
217  if (edgeToNext.second) {
218  return g[edgeToNext.first];
219  }
220  return {};
221  }
222 
225  const ConstLaneletOrArea& lanelet) const noexcept {
226  try {
227  return laneletOrAreaToVertex_.at(lanelet);
228  } catch (std::out_of_range&) {
229  return {};
230  }
231  }
232 
233  private:
234  FilteredGraph getFilteredGraph(RoutingCostId routingCostId, RelationType relations) const {
235  if (routingCostId >= numRoutingCosts_) {
236  throw InvalidInputError("Routing Cost ID is higher than the number of routing modules.");
237  }
238  return FilteredGraph(graph_, CostFilter(graph_, routingCostId, relations));
239  }
240  BaseGraphT graph_;
243 };
244 
245 class RoutingGraphGraph : public Graph<GraphType> {
246  using Graph::Graph;
247 };
248 class RouteGraph : public Graph<RouteGraphType> {
249  using Graph::Graph;
250 };
251 
252 } // namespace internal
253 } // namespace routing
254 } // namespace lanelet
lanelet::routing::internal::EdgeCostFilter::routingCostId_
RoutingCostId routingCostId_
Id of the routing cost functor to use.
Definition: Graph.h:94
lanelet::routing::internal::Graph::empty
bool empty() const noexcept
Definition: Graph.h:168
lanelet::ConstLaneletOrAreas
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
lanelet::routing::internal::Graph::withoutConflicting
FilteredGraph withoutConflicting(RoutingCostId routingCostId=0) const
Definition: Graph.h:164
lanelet::routing::internal::Graph< GraphType >::FilteredGraph
FilteredGraphT< GraphType > FilteredGraph
Definition: Graph.h:109
lanelet::routing::internal::EdgeCostFilter::relations_
RelationType relations_
Relations that pass the filter.
Definition: Graph.h:95
lanelet
lanelet::routing::internal::Graph::numRoutingCosts_
size_t numRoutingCosts_
Number of available routing cost calculation methods.
Definition: Graph.h:242
lanelet::routing::internal::Graph::withLaneChanges
FilteredGraph withLaneChanges(RoutingCostId routingCostId=0) const
Definition: Graph.h:121
lanelet::ConstArea
lanelet::routing::internal::VertexInfo::get
const ConstLaneletOrArea & get() const
Definition: Graph.h:22
lanelet::ConstLaneletOrArea
lanelet::routing::internal::EdgeInfo::routingCost
double routingCost
Calculcated routing cost. Infinity if not routable.
Definition: Graph.h:37
lanelet::routing::internal::Graph::addEdge
void addEdge(const ConstLaneletOrArea &from, const ConstLaneletOrArea &to, const EdgeInfo &edgeInfo)
Definition: Graph.h:179
lanelet::routing::internal::EdgeCostFilter
An internal edge filter to get a filtered view on the graph.
Definition: Graph.h:49
lanelet::routing::internal::FilteredRouteGraph
FilteredGraphT< RouteGraphType > FilteredRouteGraph
Definition: Graph.h:60
lanelet::routing::internal::FilteredGraphT
boost::filtered_graph< BaseGraphT, EdgeCostFilter< BaseGraphT > > FilteredGraphT
Definition: Graph.h:54
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::internal::EdgeCostFilter::EdgeCostFilter
EdgeCostFilter(const GraphT &graph, RoutingCostId routingCostId)
Constructor for a filter that includes all relation types.
Definition: Graph.h:71
lanelet::routing::internal::Graph::withAreasWithoutLaneChanges
FilteredGraph withAreasWithoutLaneChanges(RoutingCostId routingCostId=0) const
Definition: Graph.h:134
lanelet::routing::internal::RouteGraph
Definition: Graph.h:248
lanelet::routing::internal::Graph::CostFilter
EdgeCostFilter< BaseGraphT > CostFilter
Definition: Graph.h:110
lanelet::routing::internal::FilteredGraphDesc
std::pair< size_t, RelationType > FilteredGraphDesc
Definition: Graph.h:103
lanelet::routing::internal::Graph::laneletOrAreaToVertex_
LaneletOrAreaToVertex laneletOrAreaToVertex_
Mapping of lanelets/areas to vertices of the graph.
Definition: Graph.h:241
lanelet::routing::internal::EdgeCostFilter::operator()
bool operator()(const Edge &e) const
Operator that determines wheter an edge should pass the filter or not.
Definition: Graph.h:88
lanelet::routing::RelationType::Successor
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
lanelet::routing::internal::RouteVertexInfo::conflictingInMap
ConstLaneletOrAreas conflictingInMap
Definition: Graph.h:32
lanelet::routing::internal::EdgeCostFilter::EdgeCostFilter
EdgeCostFilter()=default
Needed to be able to iterate edges.
lanelet::routing::internal::Graph::addEdge
void addEdge(Vertex from, Vertex to, const EdgeInfo &edgeInfo)
Definition: Graph.h:189
lanelet::routing::internal::RouteVertexInfo::lanelet
ConstLanelet lanelet
Definition: Graph.h:30
lanelet::routing::internal::EdgeInfo::costId
RoutingCostId costId
ID of the routing cost module that was used to calculate cost.
Definition: Graph.h:38
lanelet::routing::internal::Graph::withAreasAndLaneChanges
FilteredGraph withAreasAndLaneChanges(RoutingCostId routingCostId=0) const
Definition: Graph.h:129
lanelet::routing::internal::Graph::numRoutingCosts
size_t numRoutingCosts() const noexcept
Definition: Graph.h:118
lanelet::routing::internal::Graph::adjacentLeft
FilteredGraph adjacentLeft(RoutingCostId routingCostId=0) const
Definition: Graph.h:152
lanelet::routing::internal::Graph::getVertex
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.
Definition: Graph.h:224
lanelet::routing::internal::VertexInfo::laneletOrArea
ConstLaneletOrArea laneletOrArea
Definition: Graph.h:23
lanelet::Optional
boost::optional< T > Optional
lanelet::routing::internal::FilteredRoutingGraph
FilteredGraphT< GraphType > FilteredRoutingGraph
Definition: Graph.h:59
LaneletOrArea.h
lanelet::routing::internal::GraphTraits
boost::graph_traits< GraphType > GraphTraits
Definition: Graph.h:46
lanelet::routing::internal::Graph::get
const BaseGraphT & get() const noexcept
Definition: Graph.h:116
lanelet::routing::internal::Graph::Graph
Graph(size_t numRoutingCosts)
Definition: Graph.h:114
lanelet::routing::internal::Graph::vertexLookup
const LaneletOrAreaToVertex & vertexLookup() const noexcept
Definition: Graph.h:119
lanelet::routing::internal::get
SparseColorMap::value_type get(const SparseColorMap &map, LaneletVertexId key)
Definition: GraphUtils.h:304
lanelet::routing::internal::VertexInfo
Internal information of a vertex in the graph If A* search is adapted, this could hold information ab...
Definition: Graph.h:18
lanelet::routing::internal::Graph< GraphType >::Vertex
typename boost::graph_traits< GraphType >::vertex_descriptor Vertex
Definition: Graph.h:111
lanelet::routing::internal::Graph::left
FilteredGraph left(RoutingCostId routingCostId=0) const
Definition: Graph.h:138
lanelet::routing::internal::RouteVertexInfo::laneId
LaneId laneId
Definition: Graph.h:31
lanelet::routing::internal::Graph::getEdgeInfo
Optional< EdgeInfo > getEdgeInfo(const ConstLanelet &from, const ConstLanelet &to) const noexcept
Received the edgeInfo between two given vertices.
Definition: Graph.h:203
lanelet::routing::internal::LaneletOrAreaToVertex
std::unordered_map< ConstLaneletOrArea, std::uint32_t > LaneletOrAreaToVertex
Definition: Graph.h:102
lanelet::routing::internal::RouteVertexInfo::get
const ConstLanelet & get() const
Definition: Graph.h:28
lanelet::routing::RelationType::Conflicting
@ Conflicting
Unreachable but with overlapping shape.
lanelet::routing::internal::Graph
Manages the actual routing graph and provieds different views on the edges (lazily computed)
Definition: Forward.h:17
lanelet::routing::internal::Graph::adjacentRight
FilteredGraph adjacentRight(RoutingCostId routingCostId=0) const
Definition: Graph.h:156
lanelet::routing::internal::Graph::addVertex
Vertex addVertex(const typename BaseGraphT::vertex_property_type &property)
add new lanelet to graph
Definition: Graph.h:171
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
Definition: Forward.h:44
lanelet::routing::internal::RoutingGraphGraph
Definition: Graph.h:245
lanelet::routing::internal::RouteVertexInfo
Internal information of a vertex in the route graph.
Definition: Graph.h:27
lanelet::routing::internal::Graph::getFilteredGraph
FilteredGraph getFilteredGraph(RoutingCostId routingCostId, RelationType relations) const
Definition: Graph.h:234
lanelet::routing::RelationType::Left
@ Left
(the only) directly adjacent, reachable left neighbour
lanelet::routing::RelationType::AdjacentLeft
@ AdjacentLeft
directly adjacent, unreachable left neighbor
lanelet::routing::internal::EdgeCostFilter::EdgeCostFilter
EdgeCostFilter(const GraphT &graph, RoutingCostId routingCostId, const RelationType &relation)
Constructor for a filter that includes all allowed relations in 'relation'.
Definition: Graph.h:80
lanelet::routing::internal::EdgeCostFilter::pmIds_
boost::property_map< const GraphT, RoutingCostId EdgeInfo::* >::const_type pmIds_
Property map to the routing cost IDs of the edges.
Definition: Graph.h:99
lanelet::routing::internal::Graph::getEdgeInfoFor
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.
Definition: Graph.h:210
lanelet::routing::internal::Graph::graph_
BaseGraphT graph_
The actual graph object.
Definition: Graph.h:240
lanelet::RoutingGraphError
Thrown when an there's an error in the routing graph. It will feature further information.
Definition: Exceptions.h:19
lanelet::routing::internal::Graph< GraphType >::Edge
typename boost::graph_traits< GraphType >::edge_descriptor Edge
Definition: Graph.h:112
lanelet::routing::internal::VertexInfo::area
const ConstArea & area() const
Definition: Graph.h:21
lanelet::routing::internal::Graph::right
FilteredGraph right(RoutingCostId routingCostId=0) const
Definition: Graph.h:145
lanelet::routing::RelationType::AdjacentRight
@ AdjacentRight
directly adjacent, unreachable right neighbor
lanelet::routing::internal::Graph::get
BaseGraphT & get() noexcept
Definition: Graph.h:117
lanelet::routing::LaneId
uint16_t LaneId
Definition: Forward.h:23
lanelet::routing::internal::EdgeInfo::relation
RelationType relation
Relation between the two lanelets. E.g. SUCCESSOR or CONFLICTING.
Definition: Graph.h:39
lanelet::routing::internal::EdgeCostFilter::pmRelation_
boost::property_map< const GraphT, RelationType EdgeInfo::* >::const_type pmRelation_
Property map to the relations of edges in the graph.
Definition: Graph.h:97
lanelet::ConstLanelet
lanelet::routing::internal::RouteGraphType
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo > RouteGraphType
Definition: Graph.h:45
lanelet::routing::internal::FilteredGraphTraits
boost::graph_traits< FilteredGraphT< BaseGraphT > > FilteredGraphTraits
Definition: Graph.h:57
Forward.h
lanelet::routing::allRelations
constexpr RelationType allRelations()
Definition: Forward.h:69
lanelet::routing::internal::Graph::withoutLaneChanges
FilteredGraph withoutLaneChanges(RoutingCostId routingCostId=0) const
Definition: Graph.h:125
lanelet::routing::RelationType::Right
@ Right
(the only) directly adjacent, reachable right neighbour
lanelet::routing::internal::Graph::somehowRight
FilteredGraph somehowRight(RoutingCostId routingCostId=0) const
Definition: Graph.h:148
lanelet::routing::internal::Graph::conflicting
FilteredGraph conflicting(RoutingCostId routingCostId=0) const
Definition: Graph.h:160
Exceptions.h
lanelet::routing::RelationType::Area
@ Area
Adjacent to a reachable area.
lanelet::routing::internal::VertexInfo::lanelet
const ConstLanelet & lanelet() const
Definition: Graph.h:20
lanelet::routing::internal::Graph::somehowLeft
FilteredGraph somehowLeft(RoutingCostId routingCostId=0) const
Definition: Graph.h:141
lanelet::routing::internal::GraphType
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo > GraphType
General graph type definitions.
Definition: Graph.h:43
lanelet::InvalidInputError
lanelet::routing::internal::EdgeInfo
Internal information of an edge in the graph.
Definition: Graph.h:36


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