GraphUtils.h
Go to the documentation of this file.
1 #pragma once
3 
4 #include <boost/graph/depth_first_search.hpp>
5 #include <boost/graph/two_bit_color_map.hpp>
6 
8 
9 namespace lanelet {
10 namespace routing {
11 namespace internal {
12 using LaneletVertexId = GraphTraits::vertex_descriptor;
13 using LaneletVertexIds = std::vector<LaneletVertexId>;
14 using RouteLanelets = std::set<LaneletVertexId>;
15 
16 template <typename ContainerT, typename T>
17 inline bool has(const ContainerT& c, const T& t) {
18  return std::find(c.begin(), c.end(), t) != c.end();
19 }
20 template <typename ContainerT, typename T>
21 inline bool has(const std::set<T>& c, const T& t) {
22  return c.find(t) != c.end();
23 }
24 template <RelationType R, typename GraphT, typename EdgeT>
25 inline bool hasRelation(const GraphT& g, EdgeT e) {
26  return (g[e].relation & R) != RelationType::None;
27 }
28 template <RelationType R, typename Graph>
30  auto edges = boost::out_edges(ofVertex, g);
31  auto it = std::find_if(edges.first, edges.second, [&](auto e) { return hasRelation<R>(g, e); });
32  if (it != edges.second) {
33  return boost::target(*it, g);
34  }
35  return {};
36 }
37 
38 // Class that selects between in_edges and out_edges (i wish I had c++17...)
39 template <bool Backwards>
40 struct GetEdges {};
41 template <>
42 struct GetEdges<true> {
43  template <typename Id, typename Graph>
44  inline auto operator()(Id id, Graph& g) {
45  return in_edges(id, g);
46  }
47 };
48 template <>
49 struct GetEdges<false> {
50  template <typename Id, typename Graph>
51  inline auto operator()(Id id, Graph& g) {
52  return out_edges(id, g);
53  }
54 };
55 
56 // Class that selects between in_edges and out_edges (i wish I had c++17...)
57 template <bool Backwards>
58 struct GetTarget {};
59 template <>
60 struct GetTarget<true> {
61  using T = FilteredRoutingGraph::vertex_descriptor;
62  template <typename Id, typename Graph>
63  inline T operator()(Id id, Graph& g) {
64  return boost::source(id, g);
65  }
66 };
67 template <>
68 struct GetTarget<false> {
69  using T = FilteredRoutingGraph::vertex_descriptor;
70  template <typename Id, typename Graph>
71  inline T operator()(Id id, Graph& g) {
72  return boost::target(id, g);
73  }
74 };
75 
76 template <typename Vertex, typename Graph, typename Func>
77 bool anySidewayNeighbourIs(Vertex v, const Graph& g, Func&& f) {
78  Optional<LaneletVertexId> currVertex = v;
79  while (!!currVertex && !f(*currVertex)) {
80  currVertex = getNext<RelationType::Left>(*currVertex, g);
81  }
82  if (!!currVertex) {
83  return true;
84  }
85  currVertex = getNext<RelationType::Right>(v, g);
86  while (!!currVertex && !f(*currVertex)) {
87  currVertex = getNext<RelationType::Right>(*currVertex, g);
88  }
89  return !!currVertex;
90 }
91 
92 template <typename Graph>
93 std::set<LaneletVertexId> getAllNeighbourLanelets(LaneletVertexId ofVertex, const Graph& ofRoute) {
94  std::set<LaneletVertexId> result{ofVertex};
95  Optional<LaneletVertexId> currVertex = ofVertex;
96  while (!!currVertex) {
97  result.insert(*currVertex);
98  currVertex = getNext<RelationType::Left>(*currVertex, ofRoute);
99  }
100  currVertex = ofVertex;
101  while (!!currVertex) {
102  result.insert(*currVertex);
103  currVertex = getNext<RelationType::Right>(*currVertex, ofRoute);
104  }
105  return result;
106 }
107 
110  public:
111  OriginalGraphFilter() = default;
112  OriginalGraphFilter(const GraphType& g, bool withLaneChange, RoutingCostId costId)
114  if (withLaneChange) {
115  filterMask_ |=
117  }
118  }
119  bool operator()(const GraphTraits::edge_descriptor& v) const {
120  const auto& edge = (*g_)[v];
121  return edge.costId == costId_ && (edge.relation & filterMask_) != RelationType::None;
122  }
123 
124  private:
125  const GraphType* g_;
128 };
129 using OriginalGraph = boost::filtered_graph<GraphType, OriginalGraphFilter>;
130 
133  public:
134  OnRouteFilter() = default;
135  explicit OnRouteFilter(const RouteLanelets& onRoute) : onRoute_{&onRoute} {}
136 
137  bool operator()(LaneletVertexId vertexId) const { return onRoute_->find(vertexId) != onRoute_->end(); }
138 
139  private:
141 };
142 
143 template <RelationType Relation, typename GraphType>
145  public:
146  EdgeRelationFilter() = default;
147  explicit EdgeRelationFilter(const GraphType& graph) : graph_{&graph} {}
148  bool operator()(FilteredRoutingGraph::edge_descriptor e) const {
149  auto type = (*graph_)[e].relation;
150  return (type & Relation) != RelationType::None;
151  }
152 
153  private:
154  const GraphType* graph_{};
155 };
156 
161 
164  public:
165  NoConflictingFilter() = default;
166  explicit NoConflictingFilter(const OriginalGraph& originalGraph) : originalGraph_{&originalGraph} {}
167  bool operator()(FilteredRoutingGraph::edge_descriptor e) const {
168  auto type = (*originalGraph_)[e].relation;
169  return type != RelationType::Conflicting;
170  }
171 
172  private:
174 };
175 
178  public:
179  NextToRouteFilter() = default;
180  NextToRouteFilter(const RouteLanelets& onRoute, const OriginalGraph& originalGraph)
181  : onRoute_{&onRoute}, originalGraph_{&originalGraph} {}
182 
184  // at least one out edge must be connected to lanelets on the route. This includes conflicting and adjacent!
185  if (onRoute_->find(vertexId) != onRoute_->end()) {
186  return true;
187  }
188  auto outEdges = boost::out_edges(vertexId, *originalGraph_);
189  auto connectedToRoute = std::any_of(outEdges.first, outEdges.second, [&](OriginalGraph::edge_descriptor e) {
190  auto dest = boost::target(e, *originalGraph_);
191  return onRoute_->find(dest) != onRoute_->end() ||
192  onRoute_->find(boost::source(e, *originalGraph_)) != onRoute_->end();
193  });
194  return connectedToRoute;
195  }
196 
197  private:
200 };
201 
205 
206  public:
207  OnlyDrivableEdgesWithinFilter() = default;
208  explicit OnlyDrivableEdgesWithinFilter(RouteLanelets withinLanelets, const OriginalGraph& originalGraph)
209  : drivableEdge_{originalGraph}, successorEdge_{originalGraph}, withinLanelets_{std::move(withinLanelets)} {}
210  bool operator()(FilteredRoutingGraph::edge_descriptor e) const {
211  return drivableEdge_(e) && (!successorEdge_(e) || withinLanelets_.find(e.m_source) == withinLanelets_.end());
212  }
213 
214  private:
218 };
219 
222  public:
223  ConflictingSectionFilter() = default;
224  explicit ConflictingSectionFilter(const OriginalGraph& g, const RouteLanelets& onRoute)
225  : g_{&g}, onRoute_{&onRoute} {}
226 
228  // conflicting if it is not yet part of the route but in conflict with a route lanelet
229  if (has(*onRoute_, vertexId)) {
230  return false;
231  }
232  auto outEdges = boost::out_edges(vertexId, *g_);
233  bool isNeighbour = false;
234  bool isConflicting = false;
235  std::for_each(outEdges.first, outEdges.second, [&](auto edge) {
236  if (onRoute_->find(boost::target(edge, *g_)) == onRoute_->end()) {
237  return;
238  }
239  auto type = (*g_)[edge].relation;
240  auto neighbourTypes = RelationType::Left | RelationType::Right;
242  if ((type & (neighbourTypes)) != RelationType::None) {
243  auto outEdge = boost::edge(boost::target(edge, *g_), boost::source(edge, *g_), *g_);
244  auto reverseIsNeigh = outEdge.second && ((*g_)[outEdge.first].relation & neighbourTypes) != RelationType::None;
245  isNeighbour |= reverseIsNeigh;
246  isConflicting |= !isNeighbour;
247  }
248  isConflicting |= (type & (conflictTypes)) != RelationType::None;
249  });
250  return isConflicting && !isNeighbour;
251  }
252 
253  private:
254  const OriginalGraph* g_{};
255  const RouteLanelets* onRoute_{};
256 };
257 
260  public:
261  OnRouteAndConflictFilter() = default;
262  explicit OnRouteAndConflictFilter(const RouteLanelets& onRoute, const std::vector<LaneletVertexId>& conflictWith,
263  const OriginalGraph& g)
264  : onRoute_{&onRoute}, conflictWith_{&conflictWith}, g_{&g} {}
265 
267  auto isOk = anySidewayNeighbourIs(vertexId, *g_, [&](auto v) {
268  if (!has(*onRoute_, vertexId)) {
269  return false;
270  }
271  auto outEdges = boost::out_edges(v, *g_);
272  auto isConflicting = [&](OriginalGraph::edge_descriptor e) {
274  auto type = (*g_)[e].relation;
275  return (type & conflictTypes) != RelationType::None && has(*conflictWith_, boost::target(e, *g_));
276  };
277  return v == start_ || v == end_ || std::any_of(outEdges.first, outEdges.second, isConflicting);
278  });
279  return isOk;
280  }
281 
282  void setConflicting(const LaneletVertexIds& conflictWith) { conflictWith_ = &conflictWith; }
283  void setStart(LaneletVertexId start) { start_ = start; }
284  void setEnd(LaneletVertexId end) { end_ = end; }
285 
286  private:
287  const RouteLanelets* onRoute_{};
288  const LaneletVertexIds* conflictWith_{};
289  LaneletVertexId start_{};
291  const OriginalGraph* g_{};
292 };
293 
296  using key_type = LaneletVertexId; // NOLINT
297  using value_type = boost::two_bit_color_type; // NOLINT
298  using reference = void; // NOLINT
299  using category = boost::read_write_property_map_tag; // NOLINT
300  using MapT = std::map<key_type, std::uint8_t>;
301  std::shared_ptr<MapT> data{std::make_shared<MapT>()};
302 };
303 
305  auto val = map.data->find(key);
306  if (val != map.data->end()) {
307  return static_cast<SparseColorMap::value_type>(val->second);
308  }
309  return SparseColorMap::value_type::two_bit_white;
310 }
311 
313  (*map.data)[key] = static_cast<std::uint8_t>(value);
314 }
315 
317 template <typename GraphT>
319  public:
320  using Vertices = std::vector<LaneletVertexId>;
321 
322  private:
323  template <typename Func>
324  class PathVisitor : public boost::default_dfs_visitor {
325  public:
326  PathVisitor(Func& f, Vertices& path) : path_{&path}, f_{&f} {}
327  void discover_vertex(typename GraphT::vertex_descriptor v, const GraphT& /*g*/) { // NOLINT
328  path_->push_back(v);
329  movingForward_ = true;
330  }
331  void finish_vertex(typename GraphT::vertex_descriptor v, const GraphT& /*g*/) { // NOLINT
332  if (movingForward_) {
333  (*f_)(*path_);
334  }
335  movingForward_ = false;
336  assert(!path_->empty());
337  assert(path_->back() == v);
338  path_->pop_back();
339  }
340 
341  private:
342  bool movingForward_{true};
344  const std::decay_t<Func>* f_;
345  };
346 
347  public:
348  ConnectedPathIterator() = default;
349  explicit ConnectedPathIterator(const GraphT& g) : g_{g} {}
350 
353  template <typename Func>
354  void forEachPath(LaneletVertexId start, Func&& f) {
355  assert(g_.m_vertex_pred(start));
356  path_.clear();
357  PathVisitor<Func> vis(f, path_);
358  SparseColorMap cm;
359  boost::depth_first_visit(g_, start, vis, cm);
360  }
361 
364  class PathFound {};
365  auto destinationReached = [&](const auto& path) {
366  return std::any_of(std::make_reverse_iterator(path.end()), std::make_reverse_iterator(path.begin()),
367  [&](auto p) { return p == to; });
368  };
369  try {
370  forEachPath(from, [&](const auto& path) {
371  if (destinationReached(path)) {
372  throw PathFound{};
373  }
374  });
375  } catch (PathFound) { // NOLINT(misc-throw-by-value-catch-by-reference)
376  return true;
377  }
378  return false;
379  }
380 
381  GraphT& graph() { return g_; }
382 
383  private:
384  GraphT g_;
386 };
387 
388 // Aliases for some graphs needed by us
389 using OnRouteGraph = boost::filtered_graph<OriginalGraph, boost::keep_all, OnRouteFilter>;
390 using DrivableGraph = boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter>;
391 using NoConflictingGraph = boost::filtered_graph<OriginalGraph, NoConflictingFilter>;
392 using OnlyConflictingGraph = boost::filtered_graph<OriginalGraph, OnlyConflictingFilter>;
393 using NextToRouteGraph = boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter>;
395  boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter>;
396 using ConflictsWithPathGraph = boost::filtered_graph<OriginalGraph, NoConflictingFilter, OnRouteAndConflictFilter>;
397 
398 } // namespace internal
399 } // namespace routing
400 } // namespace lanelet
lanelet::routing::internal::SparseColorMap
For graph queries, we implement our own color map because boost's color does not perform well on spar...
Definition: GraphUtils.h:295
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter::OnlyDrivableEdgesWithinFilter
OnlyDrivableEdgesWithinFilter()=default
lanelet::routing::internal::OnRouteGraph
boost::filtered_graph< OriginalGraph, boost::keep_all, OnRouteFilter > OnRouteGraph
Definition: GraphUtils.h:389
lanelet::routing::internal::ConflictingSectionFilter
Finds vertices that are in conflict or adjacent to some vertices (not reachable though bidirectional ...
Definition: GraphUtils.h:221
lanelet::routing::internal::LaneletVertexIds
std::vector< LaneletVertexId > LaneletVertexIds
Definition: GraphUtils.h:13
lanelet::routing::internal::NextToRouteFilter
Removes vertices from the graph that are not adjacent to a set of vertices. Adjacent can also mean co...
Definition: GraphUtils.h:177
lanelet::routing::internal::NoConflictingFilter::operator()
bool operator()(FilteredRoutingGraph::edge_descriptor e) const
Definition: GraphUtils.h:167
lanelet::routing::internal::ConnectedPathIterator::PathVisitor::discover_vertex
void discover_vertex(typename GraphT::vertex_descriptor v, const GraphT &)
Definition: GraphUtils.h:327
lanelet::routing::internal::GetTarget< true >::operator()
T operator()(Id id, Graph &g)
Definition: GraphUtils.h:63
lanelet::routing::internal::ConnectedPathIterator::ConnectedPathIterator
ConnectedPathIterator(const GraphT &g)
Definition: GraphUtils.h:349
lanelet::routing::internal::SparseColorMap::value_type
boost::two_bit_color_type value_type
Definition: GraphUtils.h:297
lanelet::routing::internal::EdgeRelationFilter::graph_
const GraphType * graph_
Definition: GraphUtils.h:154
lanelet::routing::internal::SparseColorMap::MapT
std::map< key_type, std::uint8_t > MapT
Definition: GraphUtils.h:300
lanelet
lanelet::routing::internal::NoConflictingFilter::NoConflictingFilter
NoConflictingFilter()=default
lanelet::routing::internal::ConflictingSectionFilter::g_
const OriginalGraph * g_
Definition: GraphUtils.h:254
lanelet::routing::internal::ConnectedPathIterator::PathVisitor::f_
const std::decay_t< Func > * f_
Definition: GraphUtils.h:344
lanelet::routing::internal::NoConflictingFilter
Removes conflicting edges from the graph.
Definition: GraphUtils.h:163
lanelet::routing::internal::ConnectedPathIterator::Vertices
std::vector< LaneletVertexId > Vertices
Definition: GraphUtils.h:320
p
BasicPoint p
lanelet::routing::internal::OriginalGraphFilter::OriginalGraphFilter
OriginalGraphFilter()=default
lanelet::Id
int64_t Id
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::internal::GetTarget< false >::T
FilteredRoutingGraph::vertex_descriptor T
Definition: GraphUtils.h:69
lanelet::routing::internal::OnRouteAndConflictFilter::setEnd
void setEnd(LaneletVertexId end)
Definition: GraphUtils.h:284
lanelet::routing::internal::GetEdges
Definition: GraphUtils.h:40
lanelet::routing::internal::ConnectedPathIterator::PathVisitor::path_
Vertices * path_
Definition: GraphUtils.h:343
lanelet::routing::internal::anySidewayNeighbourIs
bool anySidewayNeighbourIs(Vertex v, const Graph &g, Func &&f)
Definition: GraphUtils.h:77
lanelet::routing::internal::ConnectedPathIterator::PathVisitor::finish_vertex
void finish_vertex(typename GraphT::vertex_descriptor v, const GraphT &)
Definition: GraphUtils.h:331
lanelet::routing::internal::OriginalGraph
boost::filtered_graph< GraphType, OriginalGraphFilter > OriginalGraph
Definition: GraphUtils.h:129
lanelet::routing::internal::ConnectedPathIterator::g_
GraphT g_
Definition: GraphUtils.h:384
lanelet::routing::internal::SparseColorMap::data
std::shared_ptr< MapT > data
Definition: GraphUtils.h:301
lanelet::routing::internal::RouteLanelets
std::set< LaneletVertexId > RouteLanelets
Definition: GraphUtils.h:14
lanelet::routing::internal::ConnectedPathIterator::hasPathFromTo
bool hasPathFromTo(LaneletVertexId from, LaneletVertexId to)
Returns whether a path exists in the graph that connects from and to.
Definition: GraphUtils.h:363
lanelet::routing::internal::OnRouteAndConflictFilter::setConflicting
void setConflicting(const LaneletVertexIds &conflictWith)
Definition: GraphUtils.h:282
lanelet::routing::internal::GetTarget< false >::operator()
T operator()(Id id, Graph &g)
Definition: GraphUtils.h:71
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter::OnlyDrivableEdgesWithinFilter
OnlyDrivableEdgesWithinFilter(RouteLanelets withinLanelets, const OriginalGraph &originalGraph)
Definition: GraphUtils.h:208
lanelet::routing::internal::OriginalGraphFilter::OriginalGraphFilter
OriginalGraphFilter(const GraphType &g, bool withLaneChange, RoutingCostId costId)
Definition: GraphUtils.h:112
g_
DrivableGraph g_
Definition: RouteBuilder.cpp:264
lanelet::routing::RelationType::Successor
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
lanelet::routing::internal::SparseColorMap::key_type
LaneletVertexId key_type
Definition: GraphUtils.h:296
lanelet::routing::internal::GetTarget< true >::T
FilteredRoutingGraph::vertex_descriptor T
Definition: GraphUtils.h:61
lanelet::routing::internal::DrivableGraph
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter > DrivableGraph
Definition: GraphUtils.h:390
lanelet::routing::internal::OriginalGraphFilter
Filter that reduces the original graph by edges that belong to different cost types or lane changes.
Definition: GraphUtils.h:109
lanelet::routing::internal::ConflictingSectionFilter::ConflictingSectionFilter
ConflictingSectionFilter(const OriginalGraph &g, const RouteLanelets &onRoute)
Definition: GraphUtils.h:224
lanelet::routing::internal::OnRouteAndConflictFilter::OnRouteAndConflictFilter
OnRouteAndConflictFilter(const RouteLanelets &onRoute, const std::vector< LaneletVertexId > &conflictWith, const OriginalGraph &g)
Definition: GraphUtils.h:262
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter::withinLanelets_
RouteLanelets withinLanelets_
Definition: GraphUtils.h:217
lanelet::routing::internal::OnRouteFilter::OnRouteFilter
OnRouteFilter()=default
lanelet::routing::internal::has
bool has(const std::set< T > &c, const T &t)
Definition: GraphUtils.h:21
lanelet::routing::internal::ConnectedPathIterator::forEachPath
void forEachPath(LaneletVertexId start, Func &&f)
Definition: GraphUtils.h:354
lanelet::routing::internal::ConnectedPathIterator
An iterator that finds paths from a start vertex to all reachable destinations.
Definition: GraphUtils.h:318
lanelet::Optional
boost::optional< T > Optional
lanelet::routing::internal::EdgeRelationFilter::operator()
bool operator()(FilteredRoutingGraph::edge_descriptor e) const
Definition: GraphUtils.h:148
lanelet::routing::internal::ConflictOrAdjacentToRouteGraph
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter > ConflictOrAdjacentToRouteGraph
Definition: GraphUtils.h:395
lanelet::routing::internal::NextToRouteFilter::originalGraph_
const OriginalGraph * originalGraph_
Definition: GraphUtils.h:199
lanelet::routing::internal::NextToRouteGraph
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter > NextToRouteGraph
Definition: GraphUtils.h:393
lanelet::routing::internal::OnRouteFilter::OnRouteFilter
OnRouteFilter(const RouteLanelets &onRoute)
Definition: GraphUtils.h:135
lanelet::routing::internal::OnRouteAndConflictFilter
Finds vertices within a set of vertices that are in conflict with another set of vertices.
Definition: GraphUtils.h:259
lanelet::routing::internal::NoConflictingFilter::originalGraph_
const OriginalGraph * originalGraph_
Definition: GraphUtils.h:173
lanelet::routing::internal::GetTarget
Definition: GraphUtils.h:58
lanelet::routing::internal::EdgeRelationFilter::EdgeRelationFilter
EdgeRelationFilter(const GraphType &graph)
Definition: GraphUtils.h:147
lanelet::routing::internal::OnlyConflictingGraph
boost::filtered_graph< OriginalGraph, OnlyConflictingFilter > OnlyConflictingGraph
Definition: GraphUtils.h:392
lanelet::routing::internal::GetEdges< false >::operator()
auto operator()(Id id, Graph &g)
Definition: GraphUtils.h:51
vertexId
uint32_t vertexId
Definition: RoutingGraph.cpp:56
lanelet::routing::internal::OnRouteAndConflictFilter::setStart
void setStart(LaneletVertexId start)
Definition: GraphUtils.h:283
lanelet::routing::internal::hasRelation
bool hasRelation(const GraphT &g, EdgeT e)
Definition: GraphUtils.h:25
lanelet::routing::internal::EdgeRelationFilter
Definition: GraphUtils.h:144
lanelet::routing::internal::get
SparseColorMap::value_type get(const SparseColorMap &map, LaneletVertexId key)
Definition: GraphUtils.h:304
lanelet::routing::internal::OnRouteFilter::onRoute_
const RouteLanelets * onRoute_
Definition: GraphUtils.h:140
lanelet::routing::internal::ConflictingSectionFilter::operator()
bool operator()(LaneletVertexId vertexId) const
Definition: GraphUtils.h:227
lanelet::routing::internal::SparseColorMap::reference
void reference
Definition: GraphUtils.h:298
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter::drivableEdge_
OnlyDrivableEdgesFilter drivableEdge_
Definition: GraphUtils.h:215
lanelet::routing::internal::ConnectedPathIterator::PathVisitor::PathVisitor
PathVisitor(Func &f, Vertices &path)
Definition: GraphUtils.h:326
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::OriginalGraphFilter::filterMask_
RelationType filterMask_
Definition: GraphUtils.h:127
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
Definition: Forward.h:44
lanelet::routing::internal::getAllNeighbourLanelets
std::set< LaneletVertexId > getAllNeighbourLanelets(LaneletVertexId ofVertex, const Graph &ofRoute)
Definition: GraphUtils.h:93
lanelet::routing::internal::ConnectedPathIterator::PathVisitor
Definition: GraphUtils.h:324
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter::operator()
bool operator()(FilteredRoutingGraph::edge_descriptor e) const
Definition: GraphUtils.h:210
lanelet::routing::RelationType::Left
@ Left
(the only) directly adjacent, reachable left neighbour
lanelet::routing::internal::OriginalGraphFilter::costId_
RoutingCostId costId_
Definition: GraphUtils.h:126
lanelet::routing::internal::EdgeRelationFilter::EdgeRelationFilter
EdgeRelationFilter()=default
end_
LaneletVertexId end_
Definition: RouteBuilder.cpp:426
lanelet::routing::internal::OnRouteAndConflictFilter::operator()
bool operator()(LaneletVertexId vertexId) const
Definition: GraphUtils.h:266
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter
Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) OR leave the route a...
Definition: GraphUtils.h:203
lanelet::routing::RelationType::None
@ None
No relation.
lanelet::routing::internal::LaneletVertexId
GraphTraits::vertex_descriptor LaneletVertexId
Definition: GraphUtils.h:12
Graph.h
lanelet::routing::internal::OnRouteFilter::operator()
bool operator()(LaneletVertexId vertexId) const
Definition: GraphUtils.h:137
lanelet::routing::RelationType::AdjacentLeft
@ AdjacentLeft
directly adjacent, unreachable left neighbor
lanelet::routing::internal::NextToRouteFilter::onRoute_
const RouteLanelets * onRoute_
Definition: GraphUtils.h:198
lanelet::routing::internal::GetEdges< true >::operator()
auto operator()(Id id, Graph &g)
Definition: GraphUtils.h:44
c
double c
Definition: RoutingGraph.cpp:260
lanelet::routing::internal::NextToRouteFilter::NextToRouteFilter
NextToRouteFilter(const RouteLanelets &onRoute, const OriginalGraph &originalGraph)
Definition: GraphUtils.h:180
lanelet::routing::internal::OnRouteFilter
Reduces the graph to a set of desired vertices.
Definition: GraphUtils.h:132
lanelet::routing::internal::ConflictingSectionFilter::ConflictingSectionFilter
ConflictingSectionFilter()=default
lanelet::routing::RelationType::AdjacentRight
@ AdjacentRight
directly adjacent, unreachable right neighbor
lanelet::routing::internal::NextToRouteFilter::operator()
bool operator()(LaneletVertexId vertexId) const
Definition: GraphUtils.h:183
lanelet::routing::internal::OnlyDrivableEdgesFilter
EdgeRelationFilter< RelationType::Successor|RelationType::Left|RelationType::Right, OriginalGraph > OnlyDrivableEdgesFilter
Removes edges from the graph that are not drivable (e.g. adjacent or conflicing)
Definition: GraphUtils.h:159
lanelet::routing::internal::ConnectedPathIterator::path_
Vertices path_
Definition: GraphUtils.h:385
lanelet::routing::internal::OriginalGraphFilter::g_
const GraphType * g_
Definition: GraphUtils.h:125
lanelet::routing::internal::ConnectedPathIterator::graph
GraphT & graph()
Definition: GraphUtils.h:381
lanelet::routing::internal::OnlyDrivableEdgesWithinFilter::successorEdge_
SuccessorFilter successorEdge_
Definition: GraphUtils.h:216
lanelet::routing::internal::ConflictingSectionFilter::onRoute_
const RouteLanelets * onRoute_
Definition: GraphUtils.h:255
lanelet::routing::internal::SparseColorMap::category
boost::read_write_property_map_tag category
Definition: GraphUtils.h:299
lanelet::routing::internal::NoConflictingGraph
boost::filtered_graph< OriginalGraph, NoConflictingFilter > NoConflictingGraph
Definition: GraphUtils.h:391
lanelet::routing::internal::NextToRouteFilter::NextToRouteFilter
NextToRouteFilter()=default
lanelet::routing::internal::getNext
Optional< LaneletVertexId > getNext(LaneletVertexId ofVertex, const Graph &g)
Definition: GraphUtils.h:29
lanelet::routing::internal::put
void put(SparseColorMap &map, LaneletVertexId key, SparseColorMap::value_type value)
Definition: GraphUtils.h:312
lanelet::routing::internal::ConflictsWithPathGraph
boost::filtered_graph< OriginalGraph, NoConflictingFilter, OnRouteAndConflictFilter > ConflictsWithPathGraph
Definition: GraphUtils.h:396
lanelet::routing::RelationType::Right
@ Right
(the only) directly adjacent, reachable right neighbour
lanelet::routing::internal::has
bool has(const ContainerT &c, const T &t)
Definition: GraphUtils.h:17
Optional.h
lanelet::routing::internal::NoConflictingFilter::NoConflictingFilter
NoConflictingFilter(const OriginalGraph &originalGraph)
Definition: GraphUtils.h:166
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::routing::internal::OriginalGraphFilter::operator()
bool operator()(const GraphTraits::edge_descriptor &v) const
Definition: GraphUtils.h:119


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