Go to the documentation of this file.
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;
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;
250 return isConflicting && !isNeighbour;
264 : onRoute_{&onRoute}, conflictWith_{&conflictWith},
g_{&g} {}
271 auto outEdges = boost::out_edges(v, *
g_);
272 auto isConflicting = [&](OriginalGraph::edge_descriptor e) {
274 auto type = (*g_)[e].relation;
277 return v == start_ || v ==
end_ || std::any_of(outEdges.first, outEdges.second, isConflicting);
299 using category = boost::read_write_property_map_tag;
300 using MapT = std::map<key_type, std::uint8_t>;
301 std::shared_ptr<MapT> data{std::make_shared<MapT>()};
305 auto val = map.
data->find(key);
306 if (val != map.
data->end()) {
309 return SparseColorMap::value_type::two_bit_white;
313 (*map.
data)[key] =
static_cast<std::uint8_t
>(value);
317 template <
typename GraphT>
323 template <
typename Func>
329 movingForward_ =
true;
332 if (movingForward_) {
335 movingForward_ =
false;
336 assert(!path_->empty());
337 assert(path_->back() == v);
342 bool movingForward_{
true};
344 const std::decay_t<Func>*
f_;
353 template <
typename Func>
355 assert(
g_.m_vertex_pred(start));
359 boost::depth_first_visit(
g_, start, vis, cm);
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; });
370 forEachPath(from, [&](
const auto& path) {
371 if (destinationReached(path)) {
375 }
catch (PathFound) {
389 using OnRouteGraph = boost::filtered_graph<OriginalGraph, boost::keep_all, OnRouteFilter>;
390 using DrivableGraph = boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter>;
393 using NextToRouteGraph = boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter>;
395 boost::filtered_graph<OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter>;
For graph queries, we implement our own color map because boost's color does not perform well on spar...
OnlyDrivableEdgesWithinFilter()=default
boost::filtered_graph< OriginalGraph, boost::keep_all, OnRouteFilter > OnRouteGraph
Finds vertices that are in conflict or adjacent to some vertices (not reachable though bidirectional ...
std::vector< LaneletVertexId > LaneletVertexIds
Removes vertices from the graph that are not adjacent to a set of vertices. Adjacent can also mean co...
bool operator()(FilteredRoutingGraph::edge_descriptor e) const
void discover_vertex(typename GraphT::vertex_descriptor v, const GraphT &)
T operator()(Id id, Graph &g)
ConnectedPathIterator(const GraphT &g)
boost::two_bit_color_type value_type
std::map< key_type, std::uint8_t > MapT
NoConflictingFilter()=default
const std::decay_t< Func > * f_
Removes conflicting edges from the graph.
std::vector< LaneletVertexId > Vertices
OriginalGraphFilter()=default
FilteredRoutingGraph::vertex_descriptor T
void setEnd(LaneletVertexId end)
bool anySidewayNeighbourIs(Vertex v, const Graph &g, Func &&f)
void finish_vertex(typename GraphT::vertex_descriptor v, const GraphT &)
boost::filtered_graph< GraphType, OriginalGraphFilter > OriginalGraph
std::shared_ptr< MapT > data
std::set< LaneletVertexId > RouteLanelets
bool hasPathFromTo(LaneletVertexId from, LaneletVertexId to)
Returns whether a path exists in the graph that connects from and to.
void setConflicting(const LaneletVertexIds &conflictWith)
T operator()(Id id, Graph &g)
OnlyDrivableEdgesWithinFilter(RouteLanelets withinLanelets, const OriginalGraph &originalGraph)
OriginalGraphFilter(const GraphType &g, bool withLaneChange, RoutingCostId costId)
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
FilteredRoutingGraph::vertex_descriptor T
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter > DrivableGraph
Filter that reduces the original graph by edges that belong to different cost types or lane changes.
ConflictingSectionFilter(const OriginalGraph &g, const RouteLanelets &onRoute)
OnRouteAndConflictFilter(const RouteLanelets &onRoute, const std::vector< LaneletVertexId > &conflictWith, const OriginalGraph &g)
RouteLanelets withinLanelets_
bool has(const std::set< T > &c, const T &t)
void forEachPath(LaneletVertexId start, Func &&f)
An iterator that finds paths from a start vertex to all reachable destinations.
boost::optional< T > Optional
bool operator()(FilteredRoutingGraph::edge_descriptor e) const
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesFilter, ConflictingSectionFilter > ConflictOrAdjacentToRouteGraph
const OriginalGraph * originalGraph_
boost::filtered_graph< OriginalGraph, OnlyDrivableEdgesWithinFilter, NextToRouteFilter > NextToRouteGraph
OnRouteFilter(const RouteLanelets &onRoute)
Finds vertices within a set of vertices that are in conflict with another set of vertices.
const OriginalGraph * originalGraph_
EdgeRelationFilter(const GraphType &graph)
boost::filtered_graph< OriginalGraph, OnlyConflictingFilter > OnlyConflictingGraph
auto operator()(Id id, Graph &g)
void setStart(LaneletVertexId start)
bool hasRelation(const GraphT &g, EdgeT e)
SparseColorMap::value_type get(const SparseColorMap &map, LaneletVertexId key)
const RouteLanelets * onRoute_
bool operator()(LaneletVertexId vertexId) const
OnlyDrivableEdgesFilter drivableEdge_
PathVisitor(Func &f, Vertices &path)
@ Conflicting
Unreachable but with overlapping shape.
Manages the actual routing graph and provieds different views on the edges (lazily computed)
std::set< LaneletVertexId > getAllNeighbourLanelets(LaneletVertexId ofVertex, const Graph &ofRoute)
bool operator()(FilteredRoutingGraph::edge_descriptor e) const
@ Left
(the only) directly adjacent, reachable left neighbour
EdgeRelationFilter()=default
bool operator()(LaneletVertexId vertexId) const
Removes edges from the graph that are not drivable (e.g. adjacent or conflicing) OR leave the route a...
GraphTraits::vertex_descriptor LaneletVertexId
bool operator()(LaneletVertexId vertexId) const
@ AdjacentLeft
directly adjacent, unreachable left neighbor
const RouteLanelets * onRoute_
auto operator()(Id id, Graph &g)
NextToRouteFilter(const RouteLanelets &onRoute, const OriginalGraph &originalGraph)
Reduces the graph to a set of desired vertices.
ConflictingSectionFilter()=default
@ AdjacentRight
directly adjacent, unreachable right neighbor
bool operator()(LaneletVertexId vertexId) const
EdgeRelationFilter< RelationType::Successor|RelationType::Left|RelationType::Right, OriginalGraph > OnlyDrivableEdgesFilter
Removes edges from the graph that are not drivable (e.g. adjacent or conflicing)
SuccessorFilter successorEdge_
const RouteLanelets * onRoute_
boost::read_write_property_map_tag category
boost::filtered_graph< OriginalGraph, NoConflictingFilter > NoConflictingGraph
NextToRouteFilter()=default
Optional< LaneletVertexId > getNext(LaneletVertexId ofVertex, const Graph &g)
void put(SparseColorMap &map, LaneletVertexId key, SparseColorMap::value_type value)
boost::filtered_graph< OriginalGraph, NoConflictingFilter, OnRouteAndConflictFilter > ConflictsWithPathGraph
@ Right
(the only) directly adjacent, reachable right neighbour
bool has(const ContainerT &c, const T &t)
NoConflictingFilter(const OriginalGraph &originalGraph)
boost::adjacency_list< boost::vecS, boost::vecS, boost::bidirectionalS, VertexInfo, EdgeInfo > GraphType
General graph type definitions.
bool operator()(const GraphTraits::edge_descriptor &v) const
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49