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 = {}) {
26  }
27 
32  Optional<ConstLineString3d> stopLine() const;
33  Optional<LineString3d> stopLine();
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:
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 
112 
116 
118  Optional<ConstLineString3d> stopLine() const;
119  Optional<LineString3d> stopLine();
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 
194 
196  Optional<ConstLineString3d> getStopLine(const ConstLanelet& llt) const;
197  Optional<LineString3d> getStopLine(const ConstLanelet& llt);
198 
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 
252  const LineStrings3d& cancelLines = {}) {
254  }
255 
257 
261 
263 
266  std::string type() const;
267 
269 
275 
279 
281  std::vector<std::string> cancelTypes() const;
282 
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 
344  const LineStrings3d& 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:
359  const LineStrings3d& cancelLines = {});
360  explicit SpeedLimit(const RegulatoryElementDataPtr& data);
361 };
362 } // namespace lanelet
lanelet::SpeedLimit::SpeedLimit
SpeedLimit(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Definition: BasicRegulatoryElements.cpp:328
lanelet::ManeuverType
ManeuverType
Enum to distinguish maneuver types.
Definition: BasicRegulatoryElements.h:78
lanelet::TrafficSignsWithType::type
std::string type
Definition: BasicRegulatoryElements.h:222
lanelet::ConstLineStrings3d
std::vector< ConstLineString3d > ConstLineStrings3d
Definition: Forward.h:58
lanelet::RightOfWay::rightOfWayLanelets
ConstLanelets rightOfWayLanelets() const
get the lanelets have right of way
Definition: BasicRegulatoryElements.cpp:228
lanelet::LineStrings3d
std::vector< LineString3d > LineStrings3d
Definition: Forward.h:57
lanelet::TrafficSign::refLines
ConstLineStrings3d refLines() const
gets the line(s) from which a sign becomes valid.
Definition: BasicRegulatoryElements.cpp:302
lanelet::ConstLineStringsOrPolygons3d
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
Definition: LineStringOrPolygon.h:133
lanelet::RightOfWay::removeRightOfWayLanelet
bool removeRightOfWayLanelet(const Lanelet &lanelet)
Removes a right of way lanelet and returns true on success.
Definition: BasicRegulatoryElements.cpp:260
lanelet::SpeedLimit::make
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.
Definition: BasicRegulatoryElements.h:349
lanelet::TrafficSign::addRefLine
void addRefLine(const LineString3d &line)
Add a new reference line.
Definition: BasicRegulatoryElements.cpp:314
lanelet::TrafficSign::addCancellingTrafficSign
void addCancellingTrafficSign(const TrafficSignsWithType &signs)
Add new cancelling traffic sign.
Definition: BasicRegulatoryElements.cpp:336
lanelet
Definition: Attribute.h:13
lanelet::AllWayStop::trafficSigns
ConstLineStringsOrPolygons3d trafficSigns() const
get list of traffic signs that constitute this AllWayStop if existing
Definition: BasicRegulatoryElements.cpp:403
lanelet::AllWayStop::lanelets
ConstLanelets lanelets() const
get the lanelets that potentially have to yield
Definition: BasicRegulatoryElements.cpp:369
lanelet::TrafficLight::removeTrafficLight
bool removeTrafficLight(const LineStringOrPolygon3d &primitive)
remove a traffic light
Definition: BasicRegulatoryElements.cpp:197
lanelet::ConstPrimitive< RegulatoryElementData >::attributes
const AttributeMap & attributes() const
get the attributes of this primitive
Definition: Primitive.h:89
lanelet::TrafficLight::stopLine
Optional< ConstLineString3d > stopLine() const
get the stop line for the traffic light
Definition: BasicRegulatoryElements.cpp:181
lanelet::TrafficSign::removeCancellingRefLine
bool removeCancellingRefLine(const LineString3d &line)
Remove a cancelling line. Returns true on success.
Definition: BasicRegulatoryElements.cpp:324
lanelet::AttributeMap
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
Definition: Attribute.h:371
lanelet::TrafficLight::removeStopLine
void removeStopLine()
Deletes the stop line.
Definition: BasicRegulatoryElements.cpp:203
lanelet::HybridMap::insert
std::pair< iterator, bool > insert(const value_type &v)
Definition: HybridMap.h:130
lanelet::TrafficSign::trafficSigns
ConstLineStringsOrPolygons3d trafficSigns() const
returns the traffic signs
Definition: BasicRegulatoryElements.cpp:280
lanelet::RightOfWay::addYieldLanelet
void addYieldLanelet(const Lanelet &lanelet)
Add yielding lanelet.
Definition: BasicRegulatoryElements.cpp:258
lanelet::RegulatoryElementDataPtr
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
Definition: Forward.h:184
lanelet::TrafficSign::addTrafficSign
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
Definition: BasicRegulatoryElements.cpp:306
lanelet::Id
int64_t Id
Definition: Forward.h:198
lanelet::ConstLaneletWithStopLine::lanelet
ConstLanelet lanelet
Definition: BasicRegulatoryElements.h:151
lanelet::ManeuverType::Unknown
@ Unknown
Lanelet ist not part of relation.
lanelet::Lanelets
std::vector< Lanelet > Lanelets
Definition: Forward.h:113
lanelet::RegulatoryElement
A general rule or limitation for a lanelet (abstract base class)
Definition: primitives/RegulatoryElement.h:174
lanelet::TrafficLight::setStopLine
void setStopLine(const LineString3d &stopLine)
set a new stop line, overwrite the old one
Definition: BasicRegulatoryElements.cpp:201
lanelet::SpeedLimit
Represents a speed limit that affects a lanelet.
Definition: BasicRegulatoryElements.h:336
lanelet::TrafficSign
Expresses a generic traffic sign rule.
Definition: BasicRegulatoryElements.h:230
lanelet::TrafficSign::make
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.
Definition: BasicRegulatoryElements.h:250
lanelet::RightOfWay::make
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.
Definition: BasicRegulatoryElements.h:101
lanelet::SpeedLimit::RuleName
static constexpr char RuleName[]
Definition: BasicRegulatoryElements.h:339
lanelet::AttributeNamesString::SignType
static constexpr const char SignType[]
Definition: Attribute.h:235
lanelet::TrafficLight::TrafficLight
TrafficLight(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine)
Definition: BasicRegulatoryElements.cpp:177
lanelet::AllWayStop::Ptr
std::shared_ptr< AllWayStop > Ptr
Definition: BasicRegulatoryElements.h:165
lanelet::AllWayStop::addTrafficSign
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
Definition: BasicRegulatoryElements.cpp:409
lanelet::TrafficSign::cancellingTrafficSigns
ConstLineStringsOrPolygons3d cancellingTrafficSigns() const
get list of cancellingTrafficSigns, if existing
Definition: BasicRegulatoryElements.cpp:347
lanelet::ConstLaneletWithStopLine
Definition: BasicRegulatoryElements.h:150
lanelet::RightOfWay
Defines right of way restrictions.
Definition: BasicRegulatoryElements.h:87
lanelet::Optional
boost::optional< T > Optional
Definition: Optional.h:7
lanelet::Lanelet
The famous (mutable) lanelet class.
Definition: primitives/Lanelet.h:221
lanelet::TrafficLight::Ptr
std::shared_ptr< TrafficLight > Ptr
Definition: BasicRegulatoryElements.h:19
lanelet::TrafficLight
Represents a traffic light restriction on the lanelet.
Definition: BasicRegulatoryElements.h:17
lanelet::TrafficSign::cancelTypes
std::vector< std::string > cancelTypes() const
Types of the cancelling traffic signs if they exist.
Definition: BasicRegulatoryElements.cpp:353
lanelet::TrafficSign::Ptr
std::shared_ptr< TrafficSign > Ptr
Definition: BasicRegulatoryElements.h:232
lanelet::AllWayStop::getStopLine
Optional< ConstLineString3d > getStopLine(const ConstLanelet &llt) const
gets the stop line for a lanelet, if there is one
Definition: BasicRegulatoryElements.cpp:377
lanelet::TrafficSign::addCancellingRefLine
void addCancellingRefLine(const LineString3d &line)
Add a new line from where the sign becomes inactive.
Definition: BasicRegulatoryElements.cpp:320
lanelet::LaneletWithStopLine
Definition: BasicRegulatoryElements.h:146
lanelet::LineStringsOrPolygons3d
std::vector< LineStringOrPolygon3d > LineStringsOrPolygons3d
Definition: LineStringOrPolygon.h:132
lanelet::TrafficSign::RuleName
static constexpr char RuleName[]
Definition: BasicRegulatoryElements.h:233
lanelet::LaneletWithStopLine::lanelet
Lanelet lanelet
Definition: BasicRegulatoryElements.h:147
lanelet::RightOfWay::removeStopLine
void removeStopLine()
Removes the stop line.
Definition: BasicRegulatoryElements.cpp:268
lanelet::RightOfWay::addRightOfWayLanelet
void addRightOfWayLanelet(const Lanelet &lanelet)
Adds a lanelet for RightOfWay.
Definition: BasicRegulatoryElements.cpp:254
lanelet::ManeuverType::RightOfWay
@ RightOfWay
Lanelet has right of way
lanelet::RightOfWay::RuleName
static constexpr char RuleName[]
Definition: BasicRegulatoryElements.h:90
lanelet::TrafficSignsWithType
Used as input argument to create TrafficSign regElem.
Definition: BasicRegulatoryElements.h:220
lanelet::LaneletWithStopLine::stopLine
Optional< LineString3d > stopLine
Definition: BasicRegulatoryElements.h:148
lanelet::TrafficLight::RuleName
static constexpr char RuleName[]
Definition: BasicRegulatoryElements.h:20
lanelet::AllWayStop::AllWayStop
AllWayStop(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs)
Definition: BasicRegulatoryElements.cpp:449
lanelet::AllWayStop::removeTrafficSign
bool removeTrafficSign(const LineStringOrPolygon3d &sign)
removes a traffic sign and returns true on success
Definition: BasicRegulatoryElements.cpp:413
lanelet::AllWayStop
Defines an all way stop. These are a special form of right of way, where all lanelets have to yield,...
Definition: BasicRegulatoryElements.h:163
lanelet::LaneletsWithStopLines
std::vector< LaneletWithStopLine > LaneletsWithStopLines
Definition: BasicRegulatoryElements.h:154
lanelet::TrafficSignsWithType::trafficSigns
LineStringsOrPolygons3d trafficSigns
Lists relevant traffic signs.
Definition: BasicRegulatoryElements.h:221
lanelet::RightOfWay::getManeuver
ManeuverType getManeuver(const ConstLanelet &lanelet) const
returns whether a lanelet has to yield or has right of way
Definition: BasicRegulatoryElements.cpp:218
lanelet::TrafficLight::trafficLights
ConstLineStringsOrPolygons3d trafficLights() const
get the relevant traffic lights
Definition: BasicRegulatoryElements.cpp:187
lanelet::AllWayStop::RuleName
static constexpr char RuleName[]
Definition: BasicRegulatoryElements.h:166
lanelet::TrafficSign::removeTrafficSign
bool removeTrafficSign(const LineStringOrPolygon3d &sign)
remove a traffic sign and returns true on success
Definition: BasicRegulatoryElements.cpp:310
lanelet::HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::RegisterRegulatoryElement
template class for registering new RegulatoryElements.
Definition: primitives/RegulatoryElement.h:384
lanelet::TrafficSign::removeRefLine
bool removeRefLine(const LineString3d &line)
Remove a reference line. Returns true on success.
Definition: BasicRegulatoryElements.cpp:316
LineStringOrPolygon.h
lanelet::RightOfWay::yieldLanelets
ConstLanelets yieldLanelets() const
get the lanelets that have to yield
Definition: BasicRegulatoryElements.cpp:232
lanelet::AllWayStop::stopLines
ConstLineStrings3d stopLines() const
get the stop lines
Definition: BasicRegulatoryElements.cpp:373
lanelet::SpeedLimit::Ptr
std::shared_ptr< SpeedLimit > Ptr
Definition: BasicRegulatoryElements.h:338
lanelet::TrafficSign::type
std::string type() const
get the id/number of the sign(s)
Definition: BasicRegulatoryElements.cpp:286
RegulatoryElement.h
lanelet::RightOfWay::stopLine
Optional< ConstLineString3d > stopLine() const
get the stop line for the yield lanelets, if present
Definition: BasicRegulatoryElements.cpp:236
lanelet::RightOfWay::removeYieldLanelet
bool removeYieldLanelet(const Lanelet &lanelet)
Removes a yielding lanelet and returns true no success.
Definition: BasicRegulatoryElements.cpp:264
lanelet::ConstLanelet
An immutable lanelet.
Definition: primitives/Lanelet.h:131
lanelet::TrafficSign::TrafficSign
TrafficSign(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Definition: BasicRegulatoryElements.cpp:274
LineString.h
lanelet::RightOfWay::setStopLine
void setStopLine(const LineString3d &stopLine)
Overwrites the stop line.
Definition: BasicRegulatoryElements.cpp:252
lanelet::RightOfWay::Ptr
std::shared_ptr< RightOfWay > Ptr
Definition: BasicRegulatoryElements.h:89
lanelet::RegulatoryElement::data
RegulatoryElementDataPtr data()
Definition: primitives/RegulatoryElement.h:247
lanelet::RightOfWay::RightOfWay
RightOfWay(Id id, const AttributeMap &attributes, const Lanelets &rightOfWay, const Lanelets &yield, const Optional< LineString3d > &stopLine={})
Definition: BasicRegulatoryElements.cpp:214
Forward.h
lanelet::TrafficSign::removeCancellingTrafficSign
bool removeCancellingTrafficSign(const LineStringOrPolygon3d &sign)
remove a cancelling traffic sign, returns true on success
Definition: BasicRegulatoryElements.cpp:343
lanelet::AllWayStop::addLanelet
void addLanelet(const LaneletWithStopLine &lltWithStop)
Definition: BasicRegulatoryElements.cpp:417
lanelet::AllWayStop::removeLanelet
bool removeLanelet(const Lanelet &llt)
Removes a lanelet and the associated stop line, if there is one.
Definition: BasicRegulatoryElements.cpp:431
lanelet::TrafficLight::addTrafficLight
void addTrafficLight(const LineStringOrPolygon3d &primitive)
add a new traffic light
Definition: BasicRegulatoryElements.cpp:193
lanelet::ConstLaneletWithStopLine::stopLine
Optional< ConstLineString3d > stopLine
Definition: BasicRegulatoryElements.h:152
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
Definition: Forward.h:114
lanelet::SpeedLimit::make
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.
Definition: BasicRegulatoryElements.h:342
lanelet::TrafficLight::make
static Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
Definition: BasicRegulatoryElements.h:23
lanelet::AllWayStop::make
static Ptr make(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs={})
Create a valid all way stop object.
Definition: BasicRegulatoryElements.h:175
lanelet::ManeuverType::Yield
@ Yield
lanelet::TrafficSign::cancelLines
ConstLineStrings3d cancelLines() const
gets the line(s) from which a sign becomes invalid.
Definition: BasicRegulatoryElements.cpp:365


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52