5 #include <boost/graph/breadth_first_search.hpp>
6 #include <boost/graph/depth_first_search.hpp>
7 #include <unordered_set>
16 template <
typename Graph,
typename StartVertex,
typename Visitor>
17 void breadthFirstSearch(
const Graph& g, StartVertex v, Visitor vis) {
19 boost::queue<StartVertex> q;
20 boost::breadth_first_visit(g, v, q, vis, cm);
23 struct VisitationCount {
31 class VisitedLaneletGraph {
32 using VisitedCounters = std::map<NextToRouteGraph::vertex_descriptor, Optional<VisitationCount>>;
35 using VisitedVertex = VisitedCounters::value_type;
47 auto type = g[e].relation;
48 assert(!!
visited_[v] &&
"init() should make sure vertex is valid!");
50 auto dest = boost::target(e, g);
57 assert(
false &&
"This is not possible if the edge filter did his job!");
67 if (vertex.first == llt || !vertex.second || !vertex.second->isLeaf()) {
79 vertex.second.reset();
84 template <
typename Func>
85 void forAllValidLanelets(Func&& f)
const {
86 for (
const auto& vertex :
visited_) {
87 if (!!vertex.second && !vertex.second->isLeaf()) {
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) {
109 auto vertex =
visited_.find(boost::source(e, g));
110 if (vertex ==
visited_.end() || !vertex->second) {
114 vertex->second->numFollowers--;
115 }
else if (vertex->second->numLaneChangesOut > 0) {
116 vertex->second->numLaneChangesOut--;
125 class NeighbouringGraphVisitor :
public boost::default_bfs_visitor {
127 explicit NeighbouringGraphVisitor(VisitedLaneletGraph& counter) :
counter_{&counter} {}
130 template <
typename GraphType>
137 template <
typename GraphType>
138 void examine_edge(NextToRouteGraph::edge_descriptor e,
const GraphType& g)
const {
139 assert(
vCurr_ == boost::source(e, g) &&
"Breadth first search seems to iterate in a weird manner");
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 {
153 explicit GraphVisitor(
RouteLanelets& lanelets) : lanelets_{&lanelets} {}
156 lanelets_->insert(v);
163 LeftAndRightGraph graph{g, LeftAndRightFilter{g}};
165 breadthFirstSearch(graph, llt, GraphVisitor{leftAndRightLanelets});
166 return leftAndRightLanelets;
170 if (initialRoute.empty() || initialRoute.front() == initialRoute.back()) {
173 return getLeftAndRightLanelets(initialRoute.back(), originalGraph);
178 class PathsOutOfRouteFinder {
182 gRoute_{g, {}, OnRouteFilter{llts}},
183 gNoConf_{g, NoConflictingFilter{g}},
195 template <
typename Func>
196 void forEachVertexOutOfRoute(
const VisitedLaneletGraph& visited, Func&& f) {
199 visited.forAllValidLanelets([&](
const VisitedLaneletGraph::VisitedVertex& v) {
201 newConflictingVertices_.push_back(v.first);
205 auto testIfPathIsPermitted = [&](
auto& path) {
207 if (this->neverConflictsWithRoute(path) || this->alwaysConflictsWithRoute(path)) {
208 for (
auto& vertex : path) {
215 auto inEdges = boost::in_edges(newVertex,
g_);
216 auto connectsToRoute = [&](
auto e) {
218 return hasRelation<AllowedRelation>(
g_, e) &&
has(*
llts_, boost::source(e,
g_));
220 if (std::any_of(inEdges.first, inEdges.second, connectsToRoute)) {
221 iterRoute_.forEachPath(newVertex, testIfPathIsPermitted);
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)); });
244 return std::all_of(path.begin(), path.end(), isAdjacentToRoute);
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) {
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);
262 return iterPath_.hasPathFromTo(from, to);
270 ConnectedPathIterator<ConflictOrAdjacentToRouteGraph>
iterRoute_;
271 ConnectedPathIterator<ConflictsWithPathGraph>
iterPath_;
276 class RouteConstructionVisitor :
public boost::default_bfs_visitor {
278 RouteConstructionVisitor() =
default;
279 RouteConstructionVisitor(
const OriginalGraph& graph, RouteGraph& routeGraph)
284 auto llt = g[v].lanelet();
295 void examine_edge(OnRouteGraph::edge_descriptor e,
const OnRouteGraph& g) {
296 auto dest = boost::target(e, g);
297 auto llt = g[dest].lanelet();
299 const auto newLane = isDifferentLane(e, g);
300 auto type = g[e].relation;
303 destVertex =
routeGraph_->addVertex(RouteVertexInfo{llt, laneId, {}});
305 routeGraph()[
sourceElem_].laneId != routeGraph()[*destVertex].laneId) {
308 setLaneIdFromTo(routeGraph()[*destVertex].laneId, routeGraph()[
sourceElem_].laneId);
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);
325 for (
auto elem : g.vertex_set()) {
326 if (g[elem].laneId == from) {
332 static bool isDifferentLane(OnRouteGraph::edge_descriptor e,
const OnRouteGraph& g) {
338 auto dest = boost::target(e, g);
339 if (!hasOneSuccessor(boost::in_edges(dest, g), g)) {
342 auto source = boost::source(e, g);
343 return !hasOneSuccessor(boost::out_edges(source, g), g);
347 auto inEdges = boost::in_edges(v, g);
349 *std::find_if(inEdges.first, inEdges.second, [&](
auto e) { return g[e].relation == RelationType::Successor; });
350 return boost::source(e, g);
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) {
358 if (oneMoreEdge && hasOneEdge) {
361 hasOneEdge |= oneMoreEdge;
374 class RouteUnderConstruction {
376 RouteUnderConstruction(
const std::vector<LaneletVertexId>& initialRoute,
const OriginalGraph& originalGraph)
377 :
begin_{initialRoute.front()},
378 end_{initialRoute.back()},
383 OnlyDrivableEdgesWithinFilter{lastLanelets(initialRoute, originalGraph),
originalGraph_},
390 bool addAdjacentLaneletsToRoute() {
404 bool progress =
false;
411 auto routeGraph = std::make_unique<RouteGraph>(1);
413 RouteConstructionVisitor visitor(theGraph, *routeGraph);
416 if (!routeGraph->getVertex(thePath.back())) {
419 auto& g = routeGraph->get();
421 return Route(thePath, std::move(routeGraph), std::move(map));
446 RouteUnderConstruction routeUnderConstruction{vertexIds, originalGraph};
448 bool progress =
true;
450 progress = routeUnderConstruction.addAdjacentLaneletsToRoute();
452 return routeUnderConstruction.finalizeRoute(originalGraph, path);