RouteBuilder.cpp
Go to the documentation of this file.
2 
4 
5 #include <boost/graph/breadth_first_search.hpp>
6 #include <boost/graph/depth_first_search.hpp>
7 #include <unordered_set>
8 
11 
12 namespace lanelet {
13 namespace routing {
14 namespace internal {
15 namespace {
16 template <typename Graph, typename StartVertex, typename Visitor>
17 void breadthFirstSearch(const Graph& g, StartVertex v, Visitor vis) {
18  SparseColorMap cm;
19  boost::queue<StartVertex> q;
20  boost::breadth_first_visit(g, v, q, vis, cm);
21 }
22 
23 struct VisitationCount {
24  bool isLeaf() const { return numFollowers + numLaneChangesOut == 0; }
25  unsigned numFollowers{};
26  unsigned numLaneChangesOut{};
27 };
28 
31 class VisitedLaneletGraph {
32  using VisitedCounters = std::map<NextToRouteGraph::vertex_descriptor, Optional<VisitationCount>>;
33 
34  public:
35  using VisitedVertex = VisitedCounters::value_type;
36 
37  explicit VisitedLaneletGraph(const RouteLanelets& llts) : routeLanelets_{&llts} {}
38 
40  void init(LaneletVertexId v) {
41  assert(!visited_[v]);
42  visited_[v] = VisitationCount{};
43  }
44 
46  void add(LaneletVertexId v, NextToRouteGraph::edge_descriptor e, const NextToRouteGraph& g) {
47  auto type = g[e].relation;
48  assert(!!visited_[v] && "init() should make sure vertex is valid!");
49  if (type == RelationType::Left || type == RelationType::Right) {
50  auto dest = boost::target(e, g);
51  if (routeLanelets_->find(dest) != routeLanelets_->end()) {
52  visited_[v]->numLaneChangesOut++;
53  }
54  } else if (type == RelationType::Successor) {
55  visited_[v]->numFollowers++;
56  } else {
57  assert(false && "This is not possible if the edge filter did his job!");
58  }
59  }
60 
62  void pruneLeafsExcluding(LaneletVertexId llt, const NextToRouteGraph& g) {
63  bool progress = true;
64  while (progress) {
65  progress = false;
66  for (auto& vertex : visited_) {
67  if (vertex.first == llt || !vertex.second || !vertex.second->isLeaf()) {
68  continue;
69  }
70  progress = true;
71  remove(vertex, g);
72  }
73  }
74  }
75 
77  void clear() {
78  for (auto& vertex : visited_) {
79  vertex.second.reset();
80  }
81  }
82 
84  template <typename Func>
85  void forAllValidLanelets(Func&& f) const {
86  for (const auto& vertex : visited_) {
87  if (!!vertex.second && !vertex.second->isLeaf()) {
88  f(vertex);
89  }
90  }
91  }
92 
94  void remove(LaneletVertexId v, const NextToRouteGraph& g) {
95  auto iter = visited_.find(v);
96  assert(iter != visited_.end());
97  remove(*iter, g);
98  }
99 
100  private:
101  void remove(VisitedCounters::value_type& v, const NextToRouteGraph& g) {
102  v.second.reset();
103  auto inEdges = boost::in_edges(v.first, g);
104  std::for_each(inEdges.first, inEdges.second, [&](NextToRouteGraph::edge_descriptor e) {
105  auto relation = g[e].relation;
106  if ((relation & (RelationType::Successor | RelationType::Left | RelationType::Right)) == RelationType::None) {
107  return;
108  }
109  auto vertex = visited_.find(boost::source(e, g));
110  if (vertex == visited_.end() || !vertex->second) {
111  return;
112  }
113  if (relation == RelationType::Successor && vertex->second->numFollowers > 0) {
114  vertex->second->numFollowers--;
115  } else if (vertex->second->numLaneChangesOut > 0) { // implies left or right
116  vertex->second->numLaneChangesOut--;
117  }
118  });
119  }
120  VisitedCounters visited_;
122 };
123 
125 class NeighbouringGraphVisitor : public boost::default_bfs_visitor {
126  public:
127  explicit NeighbouringGraphVisitor(VisitedLaneletGraph& counter) : counter_{&counter} {}
128 
129  // called by boost graph on a new vertex
130  template <typename GraphType>
131  void examine_vertex(LaneletVertexId v, const GraphType& /*g*/) { // NOLINT
132  counter_->init(v);
133  vCurr_ = v;
134  }
135 
136  // called directly after an all its edges
137  template <typename GraphType>
138  void examine_edge(NextToRouteGraph::edge_descriptor e, const GraphType& g) const { // NOLINT
139  assert(vCurr_ == boost::source(e, g) && "Breadth first search seems to iterate in a weird manner");
140  counter_->add(vCurr_, e, g);
141  }
142 
143  private:
145  VisitedLaneletGraph* counter_;
146 };
147 
148 RouteLanelets getLeftAndRightLanelets(const LaneletVertexId& llt, const OriginalGraph& g) {
149  using LeftAndRightFilter = EdgeRelationFilter<RelationType::Left | RelationType::Right, OriginalGraph>;
150  using LeftAndRightGraph = boost::filtered_graph<OriginalGraph, LeftAndRightFilter>;
151  class GraphVisitor : public boost::default_bfs_visitor {
152  public:
153  explicit GraphVisitor(RouteLanelets& lanelets) : lanelets_{&lanelets} {}
154  // called by boost graph on a new vertex
155  void examine_vertex(LaneletVertexId v, const LeftAndRightGraph& /*g*/) { // NOLINT
156  lanelets_->insert(v);
157  }
158 
159  private:
160  RouteLanelets* lanelets_;
161  };
162 
163  LeftAndRightGraph graph{g, LeftAndRightFilter{g}};
164  RouteLanelets leftAndRightLanelets;
165  breadthFirstSearch(graph, llt, GraphVisitor{leftAndRightLanelets});
166  return leftAndRightLanelets;
167 }
168 
169 RouteLanelets lastLanelets(const std::vector<LaneletVertexId>& initialRoute, const OriginalGraph& originalGraph) {
170  if (initialRoute.empty() || initialRoute.front() == initialRoute.back()) {
171  return {};
172  }
173  return getLeftAndRightLanelets(initialRoute.back(), originalGraph);
174 }
175 
178 class PathsOutOfRouteFinder {
179  public:
180  PathsOutOfRouteFinder(const OriginalGraph& g, const RouteLanelets& llts)
181  : g_{g, OnlyDrivableEdgesFilter{g}},
182  gRoute_{g, {}, OnRouteFilter{llts}},
183  gNoConf_{g, NoConflictingFilter{g}},
184  conflictsWithRoute_{g, llts},
186  iterPath_{ConflictsWithPathGraph{g, NoConflictingFilter{g},
187  OnRouteAndConflictFilter{llts, newConflictingVertices_, g}}},
188  llts_{&llts} {}
189 
195  template <typename Func>
196  void forEachVertexOutOfRoute(const VisitedLaneletGraph& visited, Func&& f) {
197  newConflictingVertices_.clear();
198  permittedVertices_.clear();
199  visited.forAllValidLanelets([&](const VisitedLaneletGraph::VisitedVertex& v) {
200  if (conflictsWithRoute_(v.first)) {
201  newConflictingVertices_.push_back(v.first);
202  }
203  });
204  permittedVertices_.resize(newConflictingVertices_.size(), false);
205  auto testIfPathIsPermitted = [&](auto& path) {
206  // neverConflictsWith is a shortcut for cases where all lanelets are only adjacent but not conflicting.
207  if (this->neverConflictsWithRoute(path) || this->alwaysConflictsWithRoute(path)) {
208  for (auto& vertex : path) {
209  auto iter = std::find(newConflictingVertices_.begin(), newConflictingVertices_.end(), vertex);
210  permittedVertices_[std::distance(newConflictingVertices_.begin(), iter)] = true;
211  }
212  }
213  };
214  for (auto newVertex : newConflictingVertices_) {
215  auto inEdges = boost::in_edges(newVertex, g_);
216  auto connectsToRoute = [&](auto e) {
217  constexpr auto AllowedRelation = RelationType::Successor | RelationType::Left | RelationType::Right;
218  return hasRelation<AllowedRelation>(g_, e) && has(*llts_, boost::source(e, g_));
219  };
220  if (std::any_of(inEdges.first, inEdges.second, connectsToRoute)) {
221  iterRoute_.forEachPath(newVertex, testIfPathIsPermitted);
222  }
223  }
224  for (auto permit = permittedVertices_.begin(); permit != permittedVertices_.end(); ++permit) {
225  if (!*permit) {
226  f(newConflictingVertices_[size_t(std::distance(permittedVertices_.begin(), permit))]);
227  }
228  }
229  }
230 
231  private:
232  bool neverConflictsWithRoute(const LaneletVertexIds& path) {
233  auto& g = gNoConf_;
234  auto isAdjacentToRoute = [&](LaneletVertexId v) {
235  auto inEdges = boost::in_edges(v, g);
236  auto outEdges = boost::out_edges(v, g);
237  constexpr auto Adjacent =
239  return std::any_of(inEdges.first, inEdges.second,
240  [&](auto e) { return hasRelation<Adjacent>(g, e) && has(*llts_, boost::source(e, g)); }) ||
241  std::any_of(outEdges.first, outEdges.second,
242  [&](auto e) { return hasRelation<Adjacent>(g, e) && has(*llts_, boost::target(e, g)); });
243  };
244  return std::all_of(path.begin(), path.end(), isAdjacentToRoute);
245  }
246  bool alwaysConflictsWithRoute(const LaneletVertexIds& path) {
247  // We have to find a path within the route that is always conflicting with the new path
248  assert(!path.empty());
249  auto before = boost::in_edges(path.front(), g_);
250  auto after = boost::out_edges(path.back(), g_);
251  auto fromE = std::find_if(before.first, before.second, [&](auto e) { return has(*llts_, boost::source(e, g_)); });
252  auto toE = std::find_if(after.first, after.second, [&](auto e) { return has(*llts_, boost::target(e, g_)); });
253  if (fromE == before.second || toE == after.second) {
254  return false; // path is not connected to current route
255  }
256  auto from = boost::source(*fromE, g_);
257  auto to = boost::target(*toE, g_);
258  iterPath_.graph().m_vertex_pred.setConflicting(path);
259  iterPath_.graph().m_vertex_pred.setStart(from);
260  iterPath_.graph().m_vertex_pred.setEnd(to);
261 
262  return iterPath_.hasPathFromTo(from, to);
263  }
267  std::vector<LaneletVertexId> newConflictingVertices_;
268  std::vector<bool> permittedVertices_;
269  ConflictingSectionFilter conflictsWithRoute_;
270  ConnectedPathIterator<ConflictOrAdjacentToRouteGraph> iterRoute_;
271  ConnectedPathIterator<ConflictsWithPathGraph> iterPath_;
273 };
274 
276 class RouteConstructionVisitor : public boost::default_bfs_visitor {
277  public:
278  RouteConstructionVisitor() = default;
279  RouteConstructionVisitor(const OriginalGraph& graph, RouteGraph& routeGraph)
280  : graph_{&graph}, routeGraph_{&routeGraph} {}
281 
283  void examine_vertex(LaneletVertexId v, const OnRouteGraph& g) { // NOLINT
284  auto llt = g[v].lanelet();
285  if (routeGraph_->empty()) {
286  // first time
287 
288  sourceElem_ = routeGraph_->addVertex(RouteVertexInfo{llt, laneId_, {}});
289  } else {
290  sourceElem_ = *routeGraph_->getVertex(llt);
291  }
292  }
293 
295  void examine_edge(OnRouteGraph::edge_descriptor e, const OnRouteGraph& g) { // NOLINT
296  auto dest = boost::target(e, g);
297  auto llt = g[dest].lanelet();
298  auto destVertex = routeGraph_->getVertex(llt);
299  const auto newLane = isDifferentLane(e, g);
300  auto type = g[e].relation;
301  if (!destVertex) {
302  const auto laneId = newLane ? ++laneId_ : routeGraph()[sourceElem_].laneId;
303  destVertex = routeGraph_->addVertex(RouteVertexInfo{llt, laneId, {}});
304  } else if (!!destVertex && !newLane && type == RelationType::Successor &&
305  routeGraph()[sourceElem_].laneId != routeGraph()[*destVertex].laneId) {
306  // this happens if we reached a lanelet because it was part of a circle of reached through a conflicting lanelet.
307  // In this case we have to adjust lane Ids
308  setLaneIdFromTo(routeGraph()[*destVertex].laneId, routeGraph()[sourceElem_].laneId);
309  }
310  routeGraph_->addEdge(sourceElem_, *destVertex, g[e]);
311  }
312  void finish_vertex(LaneletVertexId v, const OnRouteGraph& g) { // NOLINT
313  // now that all neighbours are known, now is the time to add lanelets that conflict in the whole graph
315  auto outGraph = boost::out_edges(v, conflictInMap);
316  std::for_each(outGraph.first, outGraph.second, [&](GraphTraits::edge_descriptor e) {
317  routeGraph()[sourceElem_].conflictingInMap.push_back(g[boost::target(e, g)].laneletOrArea);
318  });
319  }
320 
321  private:
322  RouteGraphType& routeGraph() { return routeGraph_->get(); }
323  void setLaneIdFromTo(LaneId from, LaneId to) {
324  auto& g = routeGraph_->get();
325  for (auto elem : g.vertex_set()) {
326  if (g[elem].laneId == from) {
327  g[elem].laneId = to;
328  }
329  }
330  }
331 
332  static bool isDifferentLane(OnRouteGraph::edge_descriptor e, const OnRouteGraph& g) {
333  // we increment the lane id whenever the vertex has more than one predecessor or the singele predecessor has
334  // multiple follower. Non-Successor edges are always a different lane.
335  if (g[e].relation != RelationType::Successor) {
336  return true;
337  }
338  auto dest = boost::target(e, g);
339  if (!hasOneSuccessor(boost::in_edges(dest, g), g)) {
340  return true;
341  }
342  auto source = boost::source(e, g);
343  return !hasOneSuccessor(boost::out_edges(source, g), g);
344  }
345 
346  static LaneletVertexId getOnePredecessor(LaneletVertexId v, const OnRouteGraph& g) {
347  auto inEdges = boost::in_edges(v, g);
348  auto e =
349  *std::find_if(inEdges.first, inEdges.second, [&](auto e) { return g[e].relation == RelationType::Successor; });
350  return boost::source(e, g);
351  }
352 
353  template <typename EdgesT>
354  static bool hasOneSuccessor(const EdgesT& edges, const OnRouteGraph& g) {
355  bool hasOneEdge = false;
356  for (auto it = edges.first; it != edges.second; ++it) {
357  bool oneMoreEdge = g[*it].relation == RelationType::Successor;
358  if (oneMoreEdge && hasOneEdge) {
359  return false;
360  }
361  hasOneEdge |= oneMoreEdge;
362  }
363  return hasOneEdge;
364  }
365 
368  RouteGraph* routeGraph_{};
370 };
371 
374 class RouteUnderConstruction {
375  public:
376  RouteUnderConstruction(const std::vector<LaneletVertexId>& initialRoute, const OriginalGraph& originalGraph)
377  : begin_{initialRoute.front()},
378  end_{initialRoute.back()},
379  laneletsOnRoute_{initialRoute.begin(), initialRoute.end()},
380  originalGraph_{originalGraph},
381  routeGraph_{originalGraph_, {}, OnRouteFilter{laneletsOnRoute_}},
383  OnlyDrivableEdgesWithinFilter{lastLanelets(initialRoute, originalGraph), originalGraph_},
384  NextToRouteFilter{laneletsOnRoute_, originalGraph_}},
387 
390  bool addAdjacentLaneletsToRoute() {
391  laneletVisitor_.clear();
392 
393  // query the (implicit) boost graph of adjacent lanelets into the nextToRouteGraph_
394  breadthFirstSearch(nextToRouteGraph_, begin_, NeighbouringGraphVisitor{laneletVisitor_});
395 
396  // remove lanelets that do not lead to end_ from the graph
397  laneletVisitor_.pruneLeafsExcluding(end_, nextToRouteGraph_);
398 
399  // remove lanelets that (temporarily) leave the route from the graph
400  pathOutOfRouteFinder_.forEachVertexOutOfRoute(
401  laneletVisitor_, [&](auto& vertex) { laneletVisitor_.remove(vertex, nextToRouteGraph_); });
402 
403  // add the new vertices to the laneletsOnTheRoute_ and determine if we made progress.
404  bool progress = false;
405  laneletVisitor_.forAllValidLanelets([&](auto lltId) { progress |= laneletsOnRoute_.insert(lltId.first).second; });
406  return progress;
407  }
408 
410  Optional<Route> finalizeRoute(const OriginalGraph& theGraph, const LaneletPath& thePath) {
411  auto routeGraph = std::make_unique<RouteGraph>(1);
412  // Search the graph of the route. The visitor fills elements and lanebegins
413  RouteConstructionVisitor visitor(theGraph, *routeGraph);
414  breadthFirstSearch(routeGraph_, begin_, visitor);
415 
416  if (!routeGraph->getVertex(thePath.back())) {
417  return {}; // there was no path between begin and end
418  }
419  auto& g = routeGraph->get();
420  auto map = utils::createConstSubmap(utils::transform(g.vertex_set(), [&g](auto v) { return g[v].lanelet; }), {});
421  return Route(thePath, std::move(routeGraph), std::move(map));
422  }
423 
424  private:
431  VisitedLaneletGraph laneletVisitor_;
432  PathsOutOfRouteFinder pathOutOfRouteFinder_;
433 };
434 } // namespace
435 
438 Optional<Route> RouteBuilder::getRouteFromShortestPath(const LaneletPath& path, bool withLaneChanges,
439  RoutingCostId costId) {
440  // translate the lanelets to graph ids
441  auto vertexIds = utils::transform(path, [&](auto llt) { return LaneletVertexId{*graph_.getVertex(llt)}; });
442  // decide which graph we are going to use
443  OriginalGraph originalGraph{graph_.get(), OriginalGraphFilter{graph_.get(), withLaneChanges, costId}};
444 
445  // get the container for all the things
446  RouteUnderConstruction routeUnderConstruction{vertexIds, originalGraph};
447 
448  bool progress = true;
449  while (progress) {
450  progress = routeUnderConstruction.addAdjacentLaneletsToRoute();
451  }
452  return routeUnderConstruction.finalizeRoute(originalGraph, path);
453 }
454 } // namespace internal
455 } // namespace routing
456 } // namespace lanelet
lanelet::routing::internal::OnRouteGraph
boost::filtered_graph< OriginalGraph, boost::keep_all, OnRouteFilter > OnRouteGraph
Definition: GraphUtils.h:389
lanelet::routing::internal::LaneletVertexIds
std::vector< LaneletVertexId > LaneletVertexIds
Definition: GraphUtils.h:13
lanelet::utils::createConstSubmap
LaneletSubmapConstUPtr createConstSubmap(const ConstLanelets &fromLanelets, const ConstAreas &fromAreas)
routeLanelets_
const RouteLanelets * routeLanelets_
Definition: RouteBuilder.cpp:121
numFollowers
unsigned numFollowers
Definition: RouteBuilder.cpp:25
routeGraph_
RouteGraph * routeGraph_
Definition: RouteBuilder.cpp:368
RouteBuilder.h
LaneletMap.h
lanelet
conflictsWithRoute_
ConflictingSectionFilter conflictsWithRoute_
Definition: RouteBuilder.cpp:269
lanelet::routing::internal::OriginalGraph
boost::filtered_graph< GraphType, OriginalGraphFilter > OriginalGraph
Definition: GraphUtils.h:129
nextToRouteGraph_
NextToRouteGraph nextToRouteGraph_
Definition: RouteBuilder.cpp:430
lanelet::routing::internal::RouteLanelets
std::set< LaneletVertexId > RouteLanelets
Definition: GraphUtils.h:14
g_
DrivableGraph g_
Definition: RouteBuilder.cpp:264
lanelet::routing::RelationType::Successor
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
iterRoute_
ConnectedPathIterator< ConflictOrAdjacentToRouteGraph > iterRoute_
Definition: RouteBuilder.cpp:270
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::utils::transform
auto transform(Container &&c, Func f)
laneId_
LaneId laneId_
Definition: RouteBuilder.cpp:367
Optional
boost::optional< T > Optional
permittedVertices_
std::vector< bool > permittedVertices_
Definition: RouteBuilder.cpp:268
counter_
VisitedLaneletGraph * counter_
Definition: RouteBuilder.cpp:145
lanelet::routing::internal::ConflictOrAdjacentToRouteGraph
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter > ConflictOrAdjacentToRouteGraph
Definition: GraphUtils.h:395
lanelet::routing::internal::NextToRouteGraph
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter > NextToRouteGraph
Definition: GraphUtils.h:393
lanelet::routing::internal::OnlyConflictingGraph
boost::filtered_graph< OriginalGraph, OnlyConflictingFilter > OnlyConflictingGraph
Definition: GraphUtils.h:392
laneletVisitor_
VisitedLaneletGraph laneletVisitor_
Definition: RouteBuilder.cpp:431
gRoute_
OnRouteGraph gRoute_
Definition: RouteBuilder.cpp:265
iterPath_
ConnectedPathIterator< ConflictsWithPathGraph > iterPath_
Definition: RouteBuilder.cpp:271
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
Definition: Forward.h:44
GraphUtils.h
pathOutOfRouteFinder_
PathsOutOfRouteFinder pathOutOfRouteFinder_
Definition: RouteBuilder.cpp:432
lanelet::routing::RelationType::Left
@ Left
(the only) directly adjacent, reachable left neighbour
end_
LaneletVertexId end_
Definition: RouteBuilder.cpp:426
lanelet::routing::internal::LaneletVertexId
GraphTraits::vertex_descriptor LaneletVertexId
Definition: GraphUtils.h:12
Graph.h
lanelet::routing::RelationType::AdjacentLeft
@ AdjacentLeft
directly adjacent, unreachable left neighbor
gNoConf_
NoConflictingGraph gNoConf_
Definition: RouteBuilder.cpp:266
vCurr_
LaneletVertexId vCurr_
Definition: RouteBuilder.cpp:144
lanelet::routing::RelationType::AdjacentRight
@ AdjacentRight
directly adjacent, unreachable right neighbor
lanelet::routing::LaneId
uint16_t LaneId
Definition: Forward.h:23
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
begin_
LaneletVertexId begin_
Definition: RouteBuilder.cpp:425
lanelet::routing::internal::RouteGraphType
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, RouteVertexInfo, EdgeInfo > RouteGraphType
Definition: Graph.h:45
visited_
VisitedCounters visited_
Definition: RouteBuilder.cpp:120
lanelet::routing::internal::OnlyConflictingFilter
EdgeRelationFilter< RelationType::Conflicting, OriginalGraph > OnlyConflictingFilter
Definition: GraphUtils.h:160
sourceElem_
LaneletVertexId sourceElem_
Definition: RouteBuilder.cpp:369
lanelet::routing::internal::NoConflictingGraph
boost::filtered_graph< OriginalGraph, NoConflictingFilter > NoConflictingGraph
Definition: GraphUtils.h:391
newConflictingVertices_
std::vector< LaneletVertexId > newConflictingVertices_
Definition: RouteBuilder.cpp:267
originalGraph_
const OriginalGraph & originalGraph_
Lanelets already determined to be on the route.
Definition: RouteBuilder.cpp:428
numLaneChangesOut
unsigned numLaneChangesOut
Definition: RouteBuilder.cpp:26
llts_
const RouteLanelets * llts_
Definition: RouteBuilder.cpp:272
laneletsOnRoute_
RouteLanelets laneletsOnRoute_
Definition: RouteBuilder.cpp:427
graph_
const OriginalGraph * graph_
Definition: RouteBuilder.cpp:366
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
lanelet::routing::LaneletPath
A lanelet path represents a set of lanelets that can be reached in order by either driving straight o...
Definition: LaneletPath.h:13
lanelet::routing::internal::GraphType
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo > GraphType
General graph type definitions.
Definition: Graph.h:43


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