BasicRegulatoryElements.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <string>
4 
9 
10 namespace lanelet {
11 
18  public:
19  using Ptr = std::shared_ptr<TrafficLight>;
20  static constexpr char RuleName[] = "traffic_light";
24  const Optional<LineString3d>& stopLine = {}) {
25  return Ptr{new TrafficLight(id, attributes, trafficLights, stopLine)};
26  }
27 
34 
44 
52  void addTrafficLight(const LineStringOrPolygon3d& primitive);
53 
59  bool removeTrafficLight(const LineStringOrPolygon3d& primitive);
60 
65  void setStopLine(const LineString3d& stopLine);
66 
68  void removeStopLine();
69 
70  protected:
72  TrafficLight(Id id, const AttributeMap& attributes, const LineStringsOrPolygons3d& trafficLights,
73  const Optional<LineString3d>& stopLine);
75 };
76 
78 enum class ManeuverType {
79  Yield,
80  RightOfWay,
81  Unknown
82 };
83 
87 class RightOfWay : public RegulatoryElement {
88  public:
89  using Ptr = std::shared_ptr<RightOfWay>;
90  static constexpr char RuleName[] = "right_of_way";
91 
101  static Ptr make(Id id, const AttributeMap& attributes, const Lanelets& rightOfWay, const Lanelets& yield,
102  const Optional<LineString3d>& stopLine = {}) {
103  return Ptr{new RightOfWay(id, attributes, rightOfWay, yield, stopLine)};
104  }
105 
107  ManeuverType getManeuver(const ConstLanelet& lanelet) const;
108 
110  ConstLanelets rightOfWayLanelets() const;
111  Lanelets rightOfWayLanelets();
112 
114  ConstLanelets yieldLanelets() const;
115  Lanelets yieldLanelets();
116 
120 
122  void setStopLine(const LineString3d& stopLine);
123 
125  void addRightOfWayLanelet(const Lanelet& lanelet);
126 
128  void addYieldLanelet(const Lanelet& lanelet);
129 
131  bool removeRightOfWayLanelet(const Lanelet& lanelet);
132 
134  bool removeYieldLanelet(const Lanelet& lanelet);
135 
137  void removeStopLine();
138 
139  protected:
141  RightOfWay(Id id, const AttributeMap& attributes, const Lanelets& rightOfWay, const Lanelets& yield,
142  const Optional<LineString3d>& stopLine = {});
143  explicit RightOfWay(const RegulatoryElementDataPtr& data);
144 };
145 
149 };
153 };
154 using LaneletsWithStopLines = std::vector<LaneletWithStopLine>;
155 
164  public:
165  using Ptr = std::shared_ptr<AllWayStop>;
166  static constexpr char RuleName[] = "all_way_stop";
167 
175  static Ptr make(Id id, const AttributeMap& attributes, const LaneletsWithStopLines& lltsWithStop,
176  const LineStringsOrPolygons3d& signs = {}) {
177  return Ptr{new AllWayStop(id, attributes, lltsWithStop, signs)};
178  }
179 
181  ConstLanelets lanelets() const;
182  Lanelets lanelets();
183 
186  void addLanelet(const LaneletWithStopLine& lltWithStop);
187 
189  bool removeLanelet(const Lanelet& llt);
190 
192  ConstLineStrings3d stopLines() const;
193  LineStrings3d stopLines();
194 
196  Optional<ConstLineString3d> getStopLine(const ConstLanelet& llt) const;
197  Optional<LineString3d> getStopLine(const ConstLanelet& llt);
198 
200  ConstLineStringsOrPolygons3d trafficSigns() const;
201  LineStringsOrPolygons3d trafficSigns();
202 
204 
207  void addTrafficSign(const LineStringOrPolygon3d& sign);
208 
210  bool removeTrafficSign(const LineStringOrPolygon3d& sign);
211 
212  protected:
214  AllWayStop(Id id, const AttributeMap& attributes, const LaneletsWithStopLines& lltsWithStop,
215  const LineStringsOrPolygons3d& signs);
216  explicit AllWayStop(const RegulatoryElementDataPtr& data);
217 };
218 
222  std::string type{""};
223 };
226 
231  public:
232  using Ptr = std::shared_ptr<TrafficSign>;
233  static constexpr char RuleName[] = "traffic_sign";
234 
250  static Ptr make(Id id, const AttributeMap& attributes, const TrafficSignsWithType& trafficSigns,
251  const TrafficSignsWithType& cancellingTrafficSigns = {}, const LineStrings3d& refLines = {},
252  const LineStrings3d& cancelLines = {}) {
253  return Ptr(new TrafficSign(id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines));
254  }
255 
257 
259  ConstLineStringsOrPolygons3d trafficSigns() const;
260  LineStringsOrPolygons3d trafficSigns();
261 
263 
266  std::string type() const;
267 
269 
273  ConstLineStrings3d refLines() const;
274  LineStrings3d refLines();
275 
277  ConstLineStringsOrPolygons3d cancellingTrafficSigns() const;
278  LineStringsOrPolygons3d cancellingTrafficSigns();
279 
281  std::vector<std::string> cancelTypes() const;
282 
284  ConstLineStrings3d cancelLines() const;
285  LineStrings3d cancelLines();
286 
288 
291  void addTrafficSign(const LineStringOrPolygon3d& sign);
292 
294  bool removeTrafficSign(const LineStringOrPolygon3d& sign);
295 
297  void addCancellingTrafficSign(const TrafficSignsWithType& signs);
298 
300  bool removeCancellingTrafficSign(const LineStringOrPolygon3d& sign);
301 
303  void addRefLine(const LineString3d& line);
304 
306  bool removeRefLine(const LineString3d& line);
307 
309  void addCancellingRefLine(const LineString3d& line);
310 
312  bool removeCancellingRefLine(const LineString3d& line);
313 
314  protected:
315  TrafficSign(Id id, const AttributeMap& attributes, const TrafficSignsWithType& trafficSigns,
316  const TrafficSignsWithType& cancellingTrafficSigns = {}, const LineStrings3d& refLines = {},
317  const LineStrings3d& cancelLines = {});
318 
320  explicit TrafficSign(const RegulatoryElementDataPtr& data);
321 };
322 
336 class SpeedLimit : public TrafficSign {
337  public:
338  using Ptr = std::shared_ptr<SpeedLimit>;
339  static constexpr char RuleName[] = "speed_limit";
340 
342  static Ptr make(Id id, const AttributeMap& attributes, const TrafficSignsWithType& trafficSigns,
343  const TrafficSignsWithType& cancellingTrafficSigns = {}, const LineStrings3d& refLines = {},
344  const LineStrings3d& cancelLines = {}) {
345  return Ptr(new SpeedLimit(id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines));
346  }
347 
349  static Ptr make(Id id, AttributeMap attributes, const std::string& signType, const LineStrings3d& refLines = {},
350  const LineStrings3d& cancelLines = {}) {
351  attributes.insert(std::make_pair(AttributeNamesString::SignType, signType));
352  return Ptr(new SpeedLimit(id, attributes, {}, {}, refLines, cancelLines));
353  }
354 
355  protected:
357  SpeedLimit(Id id, const AttributeMap& attributes, const TrafficSignsWithType& trafficSigns,
358  const TrafficSignsWithType& cancellingTrafficSigns = {}, const LineStrings3d& refLines = {},
359  const LineStrings3d& cancelLines = {});
360  explicit SpeedLimit(const RegulatoryElementDataPtr& data);
361 };
362 } // namespace lanelet
template class for registering new RegulatoryElements.
Lanelet has right of way
std::vector< ConstLineString3d > ConstLineStrings3d
Definition: Forward.h:58
ManeuverType
Enum to distinguish maneuver types.
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
Represents a speed limit that affects a laneletA speed limit is defined by one ore more traffic signs...
Optional< ConstLineString3d > stopLine() const
get the stop line for the traffic light
static Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
type
int64_t Id
Definition: Forward.h:198
std::pair< iterator, bool > insert(const value_type &v)
Definition: HybridMap.h:130
Optional< ConstLineString3d > stopLine
const AttributeMap & attributes() const
get the attributes of this primitive
Definition: Primitive.h:89
This class holds either a LineString3d or a Polygon3d.
The famous (mutable) lanelet class.
std::vector< Lanelet > Lanelets
Definition: Forward.h:113
Optional< LineString3d > stopLine
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
Definition: Forward.h:184
Defines right of way restrictions.
Represents a traffic light restriction on the lanelet.
ConstLineStringsOrPolygons3d trafficLights() const
get the relevant traffic lights
static Ptr make(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs={})
Create a valid all way stop object.
Used as input argument to create TrafficSign regElem.
A normal 3d linestring with mutable data.
boost::optional< T > Optional
Definition: Optional.h:7
static Ptr make(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Create a speed limit regulatory element. Similar to a traffic sign.
static Ptr make(Id id, const AttributeMap &attributes, const Lanelets &rightOfWay, const Lanelets &yield, const Optional< LineString3d > &stopLine={})
Create a valid Right of Way object.
std::vector< LaneletWithStopLine > LaneletsWithStopLines
std::vector< LineStringOrPolygon3d > LineStringsOrPolygons3d
static constexpr char RuleName[]
An immutable lanelet.
void removeStopLine()
Deletes the stop line.
std::shared_ptr< RightOfWay > Ptr
void setStopLine(const LineString3d &stopLine)
set a new stop line, overwrite the old one
static Ptr make(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Create a valid TrafficSign object.
Lanelet ist not part of relation.
A general rule or limitation for a lanelet (abstract base class)
LineStringsOrPolygons3d trafficSigns
Lists relevant traffic signs.
bool removeTrafficLight(const LineStringOrPolygon3d &primitive)
remove a traffic light
std::shared_ptr< AllWayStop > Ptr
std::shared_ptr< TrafficLight > Ptr
TrafficLight(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine)
Expresses a generic traffic sign rule.
void addTrafficLight(const LineStringOrPolygon3d &primitive)
add a new traffic light
static constexpr const char SignType[]
Definition: Attribute.h:235
Defines an all way stop. These are a special form of right of way, where all lanelets have to yield...
std::shared_ptr< TrafficSign > Ptr
std::vector< LineString3d > LineStrings3d
Definition: Forward.h:57
static Ptr make(Id id, AttributeMap attributes, const std::string &signType, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Create a speed limit regulatory element only from a type or speed limit without actual sign...
std::vector< ConstLanelet > ConstLanelets
Definition: Forward.h:114


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32