Forward.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #include <memory>
6 #include <string>
7 #include <unordered_map>
8 #include <vector>
9 
10 namespace lanelet {
11 namespace routing {
12 namespace internal {
13 
14 using IdPair = std::pair<Id, Id>;
15 
16 template <typename BaseGraphT>
17 class Graph;
18 
19 class RoutingGraphGraph;
20 class RouteGraph;
21 } // namespace internal
22 
23 using LaneId = uint16_t;
24 class RoutingGraph;
25 using RoutingGraphPtr = std::shared_ptr<RoutingGraph>;
26 using RoutingGraphUPtr = std::unique_ptr<RoutingGraph>;
27 using RoutingGraphConstPtr = std::shared_ptr<const RoutingGraph>;
28 
30 using RoutingGraphContainerUPtr = std::unique_ptr<RoutingGraphContainer>;
31 
32 class Route;
33 struct LaneletRelation;
34 using LaneletRelations = std::vector<LaneletRelation>;
35 
36 using RouteUPtr = std::unique_ptr<Route>;
37 using Routes = std::vector<Route>;
38 class RoutingCost;
39 using RoutingCostPtr = std::shared_ptr<RoutingCost>;
40 using RoutingCostUPtr = std::unique_ptr<RoutingCost>;
41 using RoutingCosts = std::vector<RoutingCost>;
42 using RoutingCostUPtrs = std::vector<RoutingCostUPtr>;
43 using RoutingCostPtrs = std::vector<RoutingCostPtr>;
44 using RoutingCostId = uint16_t;
45 
46 class LaneletPath;
47 using LaneletPaths = std::vector<LaneletPath>;
48 class LaneletOrAreaPath;
49 using LaneletOrAreaPaths = std::vector<LaneletOrAreaPath>;
50 
56 enum class RelationType : uint8_t {
57  None = 0,
58  Successor = 0b1,
59  Left = 0b10,
60  Right = 0b100,
61  AdjacentLeft = 0b1000,
62  AdjacentRight = 0b10000,
63  Conflicting = 0b100000,
64  Area = 0b1000000
65 };
66 
67 using RelationUnderlyingType = std::underlying_type_t<RelationType>;
68 
69 constexpr RelationType allRelations() { return static_cast<RelationType>(0b1111111); }
70 static_assert(allRelations() > RelationType::Area, "allRelations is wrong!");
71 
75 }
76 constexpr RelationType operator&=(RelationType& r1, RelationType r2) { return r1 = r1 & r2; }
78  return RelationType(std::underlying_type_t<RelationType>(r1) | RelationUnderlyingType(r2));
79 }
80 constexpr RelationType operator|=(RelationType& r1, RelationType r2) { return r1 = r1 | r2; }
81 
82 // Used for graph export
83 inline std::string relationToString(RelationType type) {
84  switch (type) {
85  case RelationType::None:
86  return "None";
88  return "Successor";
89  case RelationType::Left:
90  return "Left";
92  return "Right";
94  return "AdjacentLeft";
96  return "AdjacentRight";
98  return "Conflicting";
99  case RelationType::Area:
100  return "Area";
101  }
102  return ""; // some compilers need that
103 }
104 
105 inline std::string relationToColor(RelationType type) {
106  switch (type) {
107  case RelationType::None:
108  return "";
110  return "green";
111  case RelationType::Left:
112  return "blue";
113  case RelationType::Right:
114  return "magenta";
116  return "red";
119  return "black";
120  case RelationType::Area:
121  return "yellow";
122  }
123  return ""; // some compilers need that
124 }
125 } // namespace routing
126 } // namespace lanelet
lanelet::routing::RoutingCostUPtr
std::unique_ptr< RoutingCost > RoutingCostUPtr
Definition: Forward.h:40
lanelet
lanelet::routing::RoutingGraphContainer
Container to associate multiple routing graphs to allow queries on multiple graphs.
Definition: RoutingGraphContainer.h:20
lanelet::routing::RoutingCostPtrs
std::vector< RoutingCostPtr > RoutingCostPtrs
Definition: Forward.h:43
lanelet::routing::relationToString
std::string relationToString(RelationType type)
Definition: Forward.h:83
lanelet::routing::RoutingCost
Abstract class to define a framework for custom routing cost calculation modules. This interfaces can...
Definition: RoutingCost.h:21
lanelet::routing::Routes
std::vector< Route > Routes
Definition: Forward.h:37
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::operator|=
constexpr RelationType operator|=(RelationType &r1, RelationType r2)
Definition: Forward.h:80
Forward.h
lanelet::routing::internal::RouteGraph
Definition: Graph.h:248
lanelet::routing::relationToColor
std::string relationToColor(RelationType type)
Definition: Forward.h:105
lanelet::routing::RelationType::Successor
@ Successor
A (the only) direct, reachable successor. Not merging and not diverging.
lanelet::routing::RoutingCostPtr
std::shared_ptr< RoutingCost > RoutingCostPtr
Definition: Forward.h:39
lanelet::Area
lanelet::routing::LaneletPaths
std::vector< LaneletPath > LaneletPaths
Definition: Forward.h:47
lanelet::routing::RouteUPtr
std::unique_ptr< Route > RouteUPtr
Definition: Forward.h:36
lanelet::routing::internal::IdPair
std::pair< Id, Id > IdPair
Definition: Forward.h:14
lanelet::routing::RoutingCosts
std::vector< RoutingCost > RoutingCosts
Definition: Forward.h:41
lanelet::routing::RoutingCostUPtrs
std::vector< RoutingCostUPtr > RoutingCostUPtrs
Definition: Forward.h:42
lanelet::routing::RoutingGraphPtr
std::shared_ptr< RoutingGraph > RoutingGraphPtr
Definition: Forward.h:25
lanelet::routing::RoutingGraphUPtr
std::unique_ptr< RoutingGraph > RoutingGraphUPtr
Definition: Forward.h:26
lanelet::routing::LaneletRelations
std::vector< LaneletRelation > LaneletRelations
Definition: Forward.h:34
lanelet::routing::LaneletRelation
Represents the relation of a lanelet to another lanelet.
Definition: Types.h:34
lanelet::routing::operator~
constexpr RelationType operator~(RelationType r)
Definition: Forward.h:72
lanelet::routing::operator|
constexpr RelationType operator|(RelationType r1, RelationType r2)
Definition: Forward.h:77
lanelet::routing::RelationType::Conflicting
@ Conflicting
Unreachable but with overlapping shape.
lanelet::routing::internal::Graph
Manages the actual routing graph and provieds different views on the edges (lazily computed)
Definition: Forward.h:17
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
Definition: Forward.h:44
lanelet::routing::LaneletOrAreaPaths
std::vector< LaneletOrAreaPath > LaneletOrAreaPaths
Definition: Forward.h:49
lanelet::routing::internal::RoutingGraphGraph
Definition: Graph.h:245
lanelet::routing::operator&=
constexpr RelationType operator&=(RelationType &r1, RelationType r2)
Definition: Forward.h:76
lanelet::routing::RelationType::Left
@ Left
(the only) directly adjacent, reachable left neighbour
lanelet::routing::LaneletOrAreaPath
Similar to LaneletPath, but can also contain areas.
Definition: LaneletPath.h:49
lanelet::routing::RelationUnderlyingType
std::underlying_type_t< RelationType > RelationUnderlyingType
Definition: Forward.h:67
lanelet::routing::RelationType::None
@ None
No relation.
lanelet::routing::RelationType::AdjacentLeft
@ AdjacentLeft
directly adjacent, unreachable left neighbor
lanelet::routing::RoutingGraph
Main class of the routing module that holds routing information and can be queried....
Definition: RoutingGraph.h:69
lanelet::routing::Route
The famous route object that marks a route from A to B.
Definition: Route.h:36
lanelet::routing::RelationType::AdjacentRight
@ AdjacentRight
directly adjacent, unreachable right neighbor
lanelet::routing::LaneId
uint16_t LaneId
Definition: Forward.h:23
lanelet::routing::RoutingGraphConstPtr
std::shared_ptr< const RoutingGraph > RoutingGraphConstPtr
Definition: Forward.h:27
lanelet::routing::allRelations
constexpr RelationType allRelations()
Definition: Forward.h:69
lanelet::routing::operator&
constexpr RelationType operator&(RelationType r1, RelationType r2)
Definition: Forward.h:73
lanelet::routing::RoutingGraphContainerUPtr
std::unique_ptr< RoutingGraphContainer > RoutingGraphContainerUPtr
Definition: Forward.h:30
lanelet::routing::RelationType::Right
@ Right
(the only) directly adjacent, reachable right neighbour
lanelet::routing::RelationType::Area
@ Area
Adjacent to a reachable area.
lanelet::routing::LaneletPath
A lanelet path represents a set of lanelets that can be reached in order by either driving straight o...
Definition: LaneletPath.h:13


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