RoutingGraphContainer.h
Go to the documentation of this file.
1 #pragma once
2 
4 #include <lanelet2_core/geometry/Lanelet.h>
5 #include <lanelet2_core/primitives/Lanelet.h>
6 
7 #include <algorithm>
8 #include <unordered_set>
9 
10 #include "lanelet2_routing/Route.h"
12 
13 namespace lanelet {
14 namespace routing {
15 
21  public:
22  using ConflictingInGraph = std::pair<size_t, ConstLanelets>;
23  using ConflictingInGraphs = std::vector<ConflictingInGraph>;
24 
27  explicit RoutingGraphContainer(std::vector<RoutingGraphConstPtr> routingGraphs) : graphs_{std::move(routingGraphs)} {}
28 
31  explicit RoutingGraphContainer(const std::vector<RoutingGraphPtr>& routingGraphs)
32  : graphs_{utils::transform(routingGraphs, [](auto& g) { return RoutingGraphConstPtr(g); })} {}
33 
40  ConstLanelets conflictingInGraph(const ConstLanelet& lanelet, size_t routingGraphId,
41  double participantHeight = .0) const {
42  if (routingGraphId >= graphs_.size()) {
43  throw InvalidInputError("Routing Graph ID is higher than the number of graphs.");
44  }
45  auto overlaps = [lanelet, participantHeight](const ConstLanelet& ll) {
46  return participantHeight != .0 ? !geometry::overlaps3d(lanelet, ll, participantHeight)
48  };
49  const auto map{graphs_[routingGraphId]->passableSubmap()};
50  ConstLanelets conflicting{map->laneletLayer.search(geometry::boundingBox2d(lanelet))};
51  auto begin = conflicting.begin();
52  auto end = conflicting.end();
53  end = std::remove(begin, end, lanelet);
54  end = std::remove_if(begin, end, overlaps);
55  conflicting.erase(end, conflicting.end());
56  return conflicting;
57  }
58 
63  ConflictingInGraphs conflictingInGraphs(const ConstLanelet& lanelet, double participantHeight = .0) const {
64  ConflictingInGraphs result;
65  for (size_t it = 0; it < graphs_.size(); it++) {
66  result.emplace_back(std::make_pair(it, conflictingInGraph(lanelet, it, participantHeight)));
67  }
68  return result;
69  }
70 
77  ConstLanelets conflictingOfRouteInGraph(const Route* route, size_t routingGraphId,
78  double participantHeight = .0) const {
79  std::unordered_set<ConstLanelet> conflicting;
80  for (const auto& it : route->laneletSubmap()->laneletLayer) {
81  ConstLanelets tempConf{conflictingInGraph(it, routingGraphId, participantHeight)};
82  conflicting.insert(tempConf.begin(), tempConf.end());
83  }
84  return ConstLanelets(conflicting.begin(), conflicting.end());
85  }
86 
91  ConflictingInGraphs conflictingOfRouteInGraphs(const Route* route, double participantHeight = .0) const {
92  ConflictingInGraphs result;
93  for (size_t it = 0; it < graphs_.size(); it++) {
94  result.emplace_back(std::make_pair(it, conflictingOfRouteInGraph(route, it, participantHeight)));
95  }
96  return result;
97  }
98 
100  const std::vector<RoutingGraphConstPtr>& routingGraphs() const { return graphs_; }
101 
102  private:
103  std::vector<RoutingGraphConstPtr> graphs_;
104 };
105 
106 } // namespace routing
107 } // namespace lanelet
RoutingGraph.h
LaneletMap.h
lanelet
lanelet::routing::RoutingGraphContainer
Container to associate multiple routing graphs to allow queries on multiple graphs.
Definition: RoutingGraphContainer.h:20
lanelet::routing::RoutingGraphContainer::RoutingGraphContainer
RoutingGraphContainer(std::vector< RoutingGraphConstPtr > routingGraphs)
Constructor of routing graph container.
Definition: RoutingGraphContainer.h:27
lanelet::routing::Route::laneletSubmap
LaneletSubmapConstPtr laneletSubmap() const noexcept
A LaneletSubmap with all lanelets that are part of the route.
Definition: Route.h:86
lanelet::routing::RoutingGraphContainer::routingGraphs
const std::vector< RoutingGraphConstPtr > & routingGraphs() const
Returns the routing graphs stored in the container.
Definition: RoutingGraphContainer.h:100
lanelet::routing::RoutingGraphContainer::graphs_
std::vector< RoutingGraphConstPtr > graphs_
Routing graphs of the container.
Definition: RoutingGraphContainer.h:103
lanelet::routing::RoutingGraphContainer::ConflictingInGraphs
std::vector< ConflictingInGraph > ConflictingInGraphs
Definition: RoutingGraphContainer.h:23
lanelet::utils::transform
auto transform(Container &&c, Func f)
Route.h
lanelet::routing::RoutingGraphContainer::conflictingInGraph
ConstLanelets conflictingInGraph(const ConstLanelet &lanelet, size_t routingGraphId, double participantHeight=.0) const
Find the conflicting lanelets of a given lanelet within a specified graph.
Definition: RoutingGraphContainer.h:40
lanelet::routing::RoutingGraphContainer::conflictingOfRouteInGraphs
ConflictingInGraphs conflictingOfRouteInGraphs(const Route *route, double participantHeight=.0) const
Find the conflicting lanelets of a given route within all graphs.
Definition: RoutingGraphContainer.h:91
lanelet::geometry::overlaps2d
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
lanelet::geometry::overlaps3d
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
lanelet::geometry::boundingBox2d
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
lanelet::routing::Route
The famous route object that marks a route from A to B.
Definition: Route.h:36
lanelet::ConstLanelet
lanelet::routing::RoutingGraphContainer::ConflictingInGraph
std::pair< size_t, ConstLanelets > ConflictingInGraph
id of conflicing graph, lanelets in conflict there
Definition: RoutingGraphContainer.h:22
lanelet::routing::RoutingGraphConstPtr
std::shared_ptr< const RoutingGraph > RoutingGraphConstPtr
Definition: Forward.h:27
lanelet::routing::RoutingGraphContainer::conflictingInGraphs
ConflictingInGraphs conflictingInGraphs(const ConstLanelet &lanelet, double participantHeight=.0) const
Find the conflicting lanelets of a given lanelet within all graphs.
Definition: RoutingGraphContainer.h:63
lanelet::routing::RoutingGraphContainer::conflictingOfRouteInGraph
ConstLanelets conflictingOfRouteInGraph(const Route *route, size_t routingGraphId, double participantHeight=.0) const
Find the conflicting lanelets of a given route within a specified graph.
Definition: RoutingGraphContainer.h:77
ll
LaneletAdjacency ll
Definition: LaneletPath.cpp:88
lanelet::routing::RoutingGraphContainer::RoutingGraphContainer
RoutingGraphContainer(const std::vector< RoutingGraphPtr > &routingGraphs)
Constructor of routing graph container.
Definition: RoutingGraphContainer.h:31
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
lanelet::InvalidInputError


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