Go to the documentation of this file.
4 #include <lanelet2_core/geometry/Lanelet.h>
5 #include <lanelet2_core/primitives/Lanelet.h>
8 #include <unordered_set>
41 double participantHeight = .0)
const {
42 if (routingGraphId >=
graphs_.size()) {
49 const auto map{
graphs_[routingGraphId]->passableSubmap()};
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());
65 for (
size_t it = 0; it <
graphs_.size(); it++) {
78 double participantHeight = .0)
const {
79 std::unordered_set<ConstLanelet> conflicting;
82 conflicting.insert(tempConf.begin(), tempConf.end());
93 for (
size_t it = 0; it <
graphs_.size(); it++) {
Container to associate multiple routing graphs to allow queries on multiple graphs.
RoutingGraphContainer(std::vector< RoutingGraphConstPtr > routingGraphs)
Constructor of routing graph container.
LaneletSubmapConstPtr laneletSubmap() const noexcept
A LaneletSubmap with all lanelets that are part of the route.
const std::vector< RoutingGraphConstPtr > & routingGraphs() const
Returns the routing graphs stored in the container.
std::vector< RoutingGraphConstPtr > graphs_
Routing graphs of the container.
std::vector< ConflictingInGraph > ConflictingInGraphs
auto transform(Container &&c, Func f)
ConstLanelets conflictingInGraph(const ConstLanelet &lanelet, size_t routingGraphId, double participantHeight=.0) const
Find the conflicting lanelets of a given lanelet within a specified graph.
ConflictingInGraphs conflictingOfRouteInGraphs(const Route *route, double participantHeight=.0) const
Find the conflicting lanelets of a given route within all graphs.
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
The famous route object that marks a route from A to B.
std::pair< size_t, ConstLanelets > ConflictingInGraph
id of conflicing graph, lanelets in conflict there
std::shared_ptr< const RoutingGraph > RoutingGraphConstPtr
ConflictingInGraphs conflictingInGraphs(const ConstLanelet &lanelet, double participantHeight=.0) const
Find the conflicting lanelets of a given lanelet within all graphs.
ConstLanelets conflictingOfRouteInGraph(const Route *route, size_t routingGraphId, double participantHeight=.0) const
Find the conflicting lanelets of a given route within a specified graph.
RoutingGraphContainer(const std::vector< RoutingGraphPtr > &routingGraphs)
Constructor of routing graph container.
std::vector< ConstLanelet > ConstLanelets
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49