4 #include <boost/graph/depth_first_search.hpp>
5 #include <boost/graph/two_bit_color_map.hpp>
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();
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();
24 template <RelationType R,
typename GraphT,
typename EdgeT>
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);
39 template <
bool Backwards>
43 template <
typename Id,
typename Graph>
45 return in_edges(
id, g);
50 template <
typename Id,
typename Graph>
52 return out_edges(
id, g);
57 template <
bool Backwards>
61 using T = FilteredRoutingGraph::vertex_descriptor;
62 template <
typename Id,
typename Graph>
64 return boost::source(
id, g);
69 using T = FilteredRoutingGraph::vertex_descriptor;
70 template <
typename Id,
typename Graph>
72 return boost::target(
id, g);
76 template <
typename Vertex,
typename Graph,
typename Func>
79 while (!!currVertex && !f(*currVertex)) {
80 currVertex = getNext<RelationType::Left>(*currVertex, g);
85 currVertex = getNext<RelationType::Right>(v, g);
86 while (!!currVertex && !f(*currVertex)) {
87 currVertex = getNext<RelationType::Right>(*currVertex, g);
92 template <
typename Graph>
94 std::set<LaneletVertexId> result{ofVertex};
96 while (!!currVertex) {
97 result.insert(*currVertex);
98 currVertex = getNext<RelationType::Left>(*currVertex, ofRoute);
100 currVertex = ofVertex;
101 while (!!currVertex) {
102 result.insert(*currVertex);
103 currVertex = getNext<RelationType::Right>(*currVertex, ofRoute);
114 if (withLaneChange) {
119 bool operator()(
const GraphTraits::edge_descriptor& v)
const {
120 const auto& edge = (*g_)[v];
129 using OriginalGraph = boost::filtered_graph<GraphType, OriginalGraphFilter>;
143 template <RelationType Relation,
typename GraphType>
148 bool operator()(FilteredRoutingGraph::edge_descriptor e)
const {
149 auto type = (*graph_)[e].relation;
167 bool operator()(FilteredRoutingGraph::edge_descriptor e)
const {
168 auto type = (*originalGraph_)[e].relation;
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();
194 return connectedToRoute;
210 bool operator()(FilteredRoutingGraph::edge_descriptor e)
const {
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()) {
239 auto type = (*
g_)[edge].relation;
246 auto outEdges = boost::out_edges(boost::target(edge, *
g_), *
g_);
247 auto reverseIsNeigh = std::any_of(outEdges.first, outEdges.second, [&](
auto outEdge) {
248 return boost::target(outEdge, *g_) == boost::source(edge, *g_) &&
249 ((*g_)[outEdge].relation & neighbourTypes) != RelationType::None;
251 isNeighbour |= reverseIsNeigh;
252 isConflicting |= !isNeighbour;
256 return isConflicting && !isNeighbour;
270 : onRoute_{&onRoute}, conflictWith_{&conflictWith},
g_{&g} {}
277 auto outEdges = boost::out_edges(v, *
g_);
278 auto isConflicting = [&](OriginalGraph::edge_descriptor e) {
280 auto type = (*g_)[e].relation;
283 return v == start_ || v ==
end_ || std::any_of(outEdges.first, outEdges.second, isConflicting);
305 using category = boost::read_write_property_map_tag;
306 using MapT = std::map<key_type, std::uint8_t>;
307 std::shared_ptr<MapT> data{std::make_shared<MapT>()};
311 auto val = map.
data->find(key);
312 if (val != map.
data->end()) {
315 return SparseColorMap::value_type::two_bit_white;
319 (*map.
data)[key] =
static_cast<std::uint8_t
>(value);
323 template <
typename GraphT>
329 template <
typename Func>
335 movingForward_ =
true;
338 if (movingForward_) {
341 movingForward_ =
false;
342 assert(!path_->empty());
343 assert(path_->back() == v);
348 bool movingForward_{
true};
350 const std::decay_t<Func>*
f_;
359 template <
typename Func>
361 assert(
g_.m_vertex_pred(start));
365 boost::depth_first_visit(
g_, start, vis, cm);
371 auto destinationReached = [&](
const auto& path) {
372 return std::any_of(std::make_reverse_iterator(path.end()), std::make_reverse_iterator(path.begin()),
373 [&](
auto p) { return p == to; });
376 forEachPath(from, [&](
const auto& path) {
377 if (destinationReached(path)) {
381 }
catch (PathFound) {
395 using OnRouteGraph = boost::filtered_graph<OriginalGraph, boost::keep_all, OnRouteFilter>;
396 using DrivableGraph = boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter>;
399 using NextToRouteGraph = boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter>;
401 boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter>;