BasicRegulatoryElements.cpp
Go to the documentation of this file.
2 
3 #include <vector>
4 
10 
11 namespace std {
13  return !lhs.expired() && !rhs.expired() && lhs.lock() == rhs.lock();
14 }
15 } // namespace std
16 namespace lanelet {
17 namespace {
18 template <typename T>
19 bool findAndErase(const T& primitive, RuleParameterMap& parameters, RoleName role) {
20  auto parameterIt = parameters.find(role);
21  if (parameterIt == parameters.end()) {
22  return false;
23  }
24  auto& parameter = parameterIt->second;
25  auto it = std::find(parameter.begin(), parameter.end(), RuleParameter(primitive));
26  if (it == parameter.end()) {
27  return false;
28  }
29  parameter.erase(it);
30  if (parameter.empty()) {
31  parameters.erase(parameterIt);
32  }
33  return true;
34 }
35 
36 template <typename T>
37 Optional<T> tryGetFront(const std::vector<T>& vec) {
38  if (vec.empty()) {
39  return {};
40  }
41  return vec.front();
42 }
43 
44 template <typename T>
45 RuleParameters toRuleParameters(const std::vector<T>& primitives) {
46  return utils::transform(primitives, [](const auto& elem) { return static_cast<RuleParameter>(elem); });
47 }
48 
49 template <>
50 RuleParameters toRuleParameters(const std::vector<LineStringOrPolygon3d>& primitives) {
51  return utils::transform(primitives, [](const auto& elem) { return elem.asRuleParameter(); });
52 }
53 
54 LineStringsOrPolygons3d getLsOrPoly(const RuleParameterMap& paramsMap, RoleName role) {
55  auto params = paramsMap.find(role);
56  if (params == paramsMap.end()) {
57  return {};
58  }
59 
61  for (const auto& param : params->second) {
62  const auto* l = boost::get<LineString3d>(&param);
63  if (l != nullptr) {
64  result.push_back(*l);
65  }
66  const auto* p = boost::get<Polygon3d>(&param);
67  if (p != nullptr) {
68  result.push_back(*p);
69  }
70  }
71  return result;
72 }
73 
74 ConstLineStringsOrPolygons3d getConstLsOrPoly(const RuleParameterMap& params, RoleName role) {
75  return utils::transform(getLsOrPoly(params, role),
76  [](auto& lsOrPoly) { return static_cast<ConstLineStringOrPolygon3d>(lsOrPoly); });
77 }
78 
79 void updateTrafficSigns(TrafficSignsWithType trafficSigns) {
80  if (!trafficSigns.type.empty()) {
81  for (auto& sign : trafficSigns.trafficSigns) {
82  sign.applyVisitor([](auto prim) { prim.setAttribute(AttributeName::Type, AttributeValueString::TrafficSign); });
83  sign.applyVisitor([&](auto prim) { prim.setAttribute(AttributeName::Subtype, trafficSigns.type); });
84  }
85  }
86 }
87 
88 RegulatoryElementDataPtr constructTrafficLightData(Id id, const AttributeMap& attributes,
89  const LineStringsOrPolygons3d& trafficLights,
90  const Optional<LineString3d>& stopLine) {
91  RuleParameterMap rpm = {{RoleNameString::Refers, toRuleParameters(trafficLights)}};
92  if (!!stopLine) {
93  rpm.insert({RoleNameString::RefLine, {*stopLine}});
94  }
95  auto data = std::make_shared<RegulatoryElementData>(id, std::move(rpm), attributes);
98  return data;
99 }
100 RegulatoryElementDataPtr constructTrafficSignData(Id id, const AttributeMap& attributes,
101  const TrafficSignsWithType& trafficSigns,
102  const TrafficSignsWithType& cancellingTrafficSigns,
103  const LineStrings3d& refLines, const LineStrings3d& cancelLines) {
104  updateTrafficSigns(trafficSigns);
105  updateTrafficSigns(cancellingTrafficSigns);
106  RuleParameterMap rpm = {{RoleNameString::Refers, toRuleParameters(trafficSigns.trafficSigns)},
107  {RoleNameString::Cancels, toRuleParameters(cancellingTrafficSigns.trafficSigns)},
108  {RoleNameString::RefLine, toRuleParameters(refLines)},
109  {RoleNameString::CancelLine, toRuleParameters(cancelLines)}};
110  auto data = std::make_shared<RegulatoryElementData>(id, std::move(rpm), attributes);
113  return data;
114 }
115 RegulatoryElementDataPtr constructSpeedLimitData(Id id, const AttributeMap& attributes,
116  const TrafficSignsWithType& trafficSigns,
117  const TrafficSignsWithType& cancellingTrafficSigns,
118  const LineStrings3d& refLines, const LineStrings3d& cancelLines) {
119  auto data = constructTrafficSignData(id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines);
121  return data;
122 }
123 RegulatoryElementDataPtr constructRightOfWayData(Id id, const AttributeMap& attributes, const Lanelets& rightOfWay,
124  const Lanelets& yield, const Optional<LineString3d>& stopLine) {
125  RuleParameterMap rpm = {{RoleNameString::RightOfWay, toRuleParameters(rightOfWay)},
126  {RoleNameString::Yield, toRuleParameters(yield)}};
127  auto data = std::make_shared<RegulatoryElementData>(id, std::move(rpm), attributes);
130  if (stopLine) {
131  data->parameters[RoleName::RefLine] = {*stopLine};
132  }
133  return data;
134 }
135 RegulatoryElementDataPtr constructAllWayStopData(Id id, const AttributeMap& attributes,
136  const LaneletsWithStopLines& lltWithStop,
137  const LineStringsOrPolygons3d& signs) {
138  RuleParameters llts =
139  utils::transform(lltWithStop, [](auto& llt) { return static_cast<RuleParameter>(llt.lanelet); });
140  auto sl = utils::createReserved<RuleParameters>(lltWithStop.size());
141  utils::forEach(lltWithStop, [&](auto& stop) {
142  if (!!stop.stopLine) {
143  sl.push_back(static_cast<RuleParameter>(*stop.stopLine));
144  }
145  });
146  RuleParameterMap rpm = {
147  {RoleNameString::Yield, llts}, {RoleNameString::RefLine, sl}, {RoleNameString::Refers, toRuleParameters(signs)}};
148  auto data = std::make_shared<RegulatoryElementData>(id, std::move(rpm), attributes);
151  return data;
152 }
153 } // namespace
154 
160 #if __cplusplus < 201703L
161 constexpr char TrafficLight::RuleName[];
162 constexpr char RightOfWay::RuleName[];
163 constexpr char TrafficSign::RuleName[];
164 constexpr char SpeedLimit::RuleName[];
165 constexpr char AllWayStop::RuleName[];
166 #endif
167 
169  if (getConstLsOrPoly(data->parameters, RoleName::Refers).empty()) {
170  throw InvalidInputError("No traffic light defined!");
171  }
172  if (getParameters<ConstLineString3d>(RoleName::RefLine).size() > 1) {
173  throw InvalidInputError("There can not exist more than one stop line!");
174  }
175 }
176 
177 TrafficLight::TrafficLight(Id id, const AttributeMap& attributes, const LineStringsOrPolygons3d& trafficLights,
178  const Optional<LineString3d>& stopLine)
179  : TrafficLight(constructTrafficLightData(id, attributes, trafficLights, stopLine)) {}
180 
182  return tryGetFront(getParameters<ConstLineString3d>(RoleName::RefLine));
183 }
184 
185 Optional<LineString3d> TrafficLight::stopLine() { return tryGetFront(getParameters<LineString3d>(RoleName::RefLine)); }
186 
188  return getConstLsOrPoly(parameters(), RoleName::Refers);
189 }
190 
192 
194  parameters()[RoleName::Refers].emplace_back(primitive.asRuleParameter());
195 }
196 
198  return findAndErase(primitive.asRuleParameter(), parameters(), RoleName::Refers);
199 }
200 
202 
204 
206  if (getParameters<WeakLanelet>(RoleName::RightOfWay).empty()) {
207  throw InvalidInputError("A maneuver must refer to at least one lanelet that has right of way!");
208  }
209  if (getParameters<WeakLanelet>(RoleName::Yield).empty()) {
210  throw InvalidInputError("A maneuver must refer to at least one lanelet that has to yield!");
211  }
212 }
213 
214 RightOfWay::RightOfWay(Id id, const AttributeMap& attributes, const Lanelets& rightOfWay, const Lanelets& yield,
215  const Optional<LineString3d>& stopLine)
216  : RightOfWay(constructRightOfWayData(id, attributes, rightOfWay, yield, stopLine)) {}
217 
221  }
223  return ManeuverType::Yield;
224  }
225  return ManeuverType::Unknown;
226 }
227 
228 ConstLanelets RightOfWay::rightOfWayLanelets() const { return getParameters<ConstLanelet>(RoleName::RightOfWay); }
229 
230 Lanelets RightOfWay::rightOfWayLanelets() { return utils::strong(getParameters<WeakLanelet>(RoleName::RightOfWay)); }
231 
232 ConstLanelets RightOfWay::yieldLanelets() const { return getParameters<ConstLanelet>(RoleName::Yield); }
233 
234 Lanelets RightOfWay::yieldLanelets() { return utils::strong(getParameters<WeakLanelet>(RoleName::Yield)); }
235 
237  auto stopLine = getParameters<ConstLineString3d>(RoleName::RefLine);
238  if (!stopLine.empty()) {
239  return stopLine.front();
240  }
241  return {};
242 }
243 
245  auto stopLine = getParameters<LineString3d>(RoleName::RefLine);
246  if (!stopLine.empty()) {
247  return stopLine.front();
248  }
249  return {};
250 }
251 
253 
255  parameters()[RoleName::RightOfWay].emplace_back(lanelet);
256 }
257 
259 
261  return findAndErase(lanelet, parameters(), RoleName::RightOfWay);
262 }
263 
265  return findAndErase(lanelet, parameters(), RoleName::Yield);
266 }
267 
269 
271  type(); // will throw if type is invalid
272 }
273 
274 TrafficSign::TrafficSign(Id id, const AttributeMap& attributes, const TrafficSignsWithType& trafficSigns,
275  const TrafficSignsWithType& cancellingTrafficSigns, const LineStrings3d& refLines,
276  const LineStrings3d& cancelLines)
277  : TrafficSign(
278  constructTrafficSignData(id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines)) {}
279 
281  return getConstLsOrPoly(parameters(), RoleName::Refers);
282 }
283 
285 
286 std::string TrafficSign::type() const {
287  auto signs = trafficSigns();
288  if (!signs.empty() &&
289  signs.front().applyVisitor([](auto& prim) { return prim.hasAttribute(AttributeName::Subtype); })) {
290  const auto& attr = signs.front().applyVisitor([](auto& prim) { return prim.attribute(AttributeName::Subtype); });
291  return attr.value();
292  }
293  if (!signs.empty()) {
294  throw InvalidInputError("Regulatory element has a traffic sign without subtype attribute!");
295  }
298  }
299  throw InvalidInputError("Regulatory element can not determine the type of the traffic sign!");
300 } // namespace lanelet
301 
302 ConstLineStrings3d TrafficSign::refLines() const { return getParameters<ConstLineString3d>(RoleName::RefLine); }
303 
304 LineStrings3d TrafficSign::refLines() { return getParameters<LineString3d>(RoleName::RefLine); }
305 
307  parameters()[RoleName::Refers].emplace_back(sign.asRuleParameter());
308 }
309 
311  return findAndErase(sign.asRuleParameter(), parameters(), RoleName::Refers);
312 }
313 
314 void TrafficSign::addRefLine(const LineString3d& line) { parameters()[RoleName::RefLine].emplace_back(line); }
315 
317  return findAndErase(line, parameters(), RoleName::RefLine);
318 }
319 
321  parameters()[RoleName::CancelLine].emplace_back(line);
322 }
323 
325  return findAndErase(line, parameters(), RoleName::CancelLine);
326 }
327 
328 SpeedLimit::SpeedLimit(Id id, const AttributeMap& attributes, const TrafficSignsWithType& trafficSigns,
329  const TrafficSignsWithType& cancellingTrafficSigns, const LineStrings3d& refLines,
330  const LineStrings3d& cancelLines)
331  : TrafficSign(
332  constructSpeedLimitData(id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines)) {}
333 
335 
337  updateTrafficSigns(signs);
338  for (const auto& sign : signs.trafficSigns) {
339  parameters()[RoleName::Cancels].emplace_back(sign.asRuleParameter());
340  }
341 }
342 
344  return findAndErase(sign.asRuleParameter(), parameters(), RoleName::Cancels);
345 }
346 
348  return getConstLsOrPoly(parameters(), RoleName::Cancels);
349 }
350 
352 
353 std::vector<std::string> TrafficSign::cancelTypes() const {
354  auto signs = cancellingTrafficSigns();
355  std::vector<std::string> types;
356  types.reserve(signs.size());
357  for (auto& sign : signs) {
358  types.push_back(sign.applyVisitor([](auto& prim) { return prim.attribute(AttributeName::Subtype); }).value());
359  }
360  std::sort(types.begin(), types.end());
361  types.erase(std::unique(types.begin(), types.end()), types.end());
362  return types;
363 }
364 
365 ConstLineStrings3d TrafficSign::cancelLines() const { return getParameters<ConstLineString3d>(RoleName::CancelLine); }
366 
367 LineStrings3d TrafficSign::cancelLines() { return getParameters<LineString3d>(RoleName::CancelLine); }
368 
369 ConstLanelets AllWayStop::lanelets() const { return getParameters<ConstLanelet>(RoleName::Yield); }
370 
371 Lanelets AllWayStop::lanelets() { return utils::strong(getParameters<WeakLanelet>(RoleName::Yield)); }
372 
373 ConstLineStrings3d AllWayStop::stopLines() const { return getParameters<ConstLineString3d>(RoleName::RefLine); }
374 
375 LineStrings3d AllWayStop::stopLines() { return getParameters<LineString3d>(RoleName::RefLine); }
376 
378  auto sl = stopLines();
379  if (sl.empty()) {
380  return {};
381  }
382  auto llts = lanelets();
383  auto it = std::find(llts.begin(), llts.end(), llt);
384  if (it == llts.end()) {
385  return {};
386  }
387  return sl.at(size_t(std::distance(llts.begin(), it)));
388 }
389 
391  auto sl = stopLines();
392  if (sl.empty()) {
393  return {};
394  }
395  auto llts = lanelets();
396  auto it = std::find(llts.begin(), llts.end(), llt);
397  if (it == llts.end()) {
398  return {};
399  }
400  return sl.at(size_t(std::distance(llts.begin(), it)));
401 }
402 
404  return getConstLsOrPoly(parameters(), RoleName::Refers);
405 }
406 
408 
410  parameters()[RoleName::Refers].push_back(sign.asRuleParameter());
411 }
412 
414  return findAndErase(sign.asRuleParameter(), parameters(), RoleName::Refers);
415 }
416 
417 void AllWayStop::addLanelet(const LaneletWithStopLine& lltWithStop) {
418  auto sl = stopLines();
419  if (sl.empty() && !lanelets().empty() && !!lltWithStop.stopLine) {
420  throw InvalidInputError("A lanelet with stop line was added, but existing lanelets don't have a stop line!");
421  }
422  if (!sl.empty() && !lltWithStop.stopLine) {
423  throw InvalidInputError("A lanelet without stopline was added, but existing lanelets have a stop line!");
424  }
425  parameters()[RoleName::Yield].emplace_back(lltWithStop.lanelet);
426  if (!!lltWithStop.stopLine) {
427  parameters()[RoleName::RefLine].emplace_back(*lltWithStop.stopLine);
428  }
429 }
430 
432  auto yieldIt = parameters().find(RoleName::Yield);
433  if (yieldIt == parameters().end()) {
434  return false;
435  }
436  auto& yieldLLts = yieldIt->second;
437  auto lltIt = std::find(yieldLLts.begin(), yieldLLts.end(), RuleParameter(llt));
438  if (lltIt == yieldLLts.end()) {
439  return false;
440  }
441  auto linesIt = parameters().find(RoleName::RefLine);
442  if (linesIt != parameters().end() && !linesIt->second.empty()) {
443  linesIt->second.erase(linesIt->second.begin() + std::distance(yieldLLts.begin(), lltIt));
444  }
445  yieldLLts.erase(lltIt);
446  return true;
447 }
448 
449 AllWayStop::AllWayStop(Id id, const AttributeMap& attributes, const LaneletsWithStopLines& lltsWithStop,
450  const LineStringsOrPolygons3d& signs)
451  : AllWayStop{constructAllWayStopData(id, attributes, lltsWithStop, signs)} {}
452 
454  auto yields = parameters().find(RoleName::Yield);
455  auto lines = parameters().find(RoleName::RefLine);
456  auto row = parameters().find(RoleName::RightOfWay);
457  if (row != parameters().end() && !row->second.empty()) {
458  throw InvalidInputError("An all way stop must not have a lanelet with right of way!");
459  }
460  if (lines == parameters().end() || lines->second.empty()) {
461  return;
462  }
463  if (yields == parameters().end() || lines->second.size() != yields->second.size()) {
464  throw InvalidInputError(
465  "Inconsistent number of lanelets and stop lines found! Either one stop line per lanelet or no stop lines!");
466  }
467 }
468 
469 } // 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::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::RoleName::Cancels
@ Cancels
primitive(s) that invalidate a rule (eg end of speed zone)
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::RoleName::RefLine
@ RefLine
The referring line where the rule becomes active.
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::utils::forEach
void forEach(Container &&c, Func &&f)
Definition: Utilities.h:226
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
Point.h
lanelet::RegulatoryElement::empty
bool empty() const
returns true if this object contains no parameters
Definition: primitives/RegulatoryElement.h:233
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::RoleName::Yield
@ Yield
A lanelet that has to yield.
lanelet::AttributeMap
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
Definition: Attribute.h:371
lanelet::ConstPrimitive< RegulatoryElementData >::hasAttribute
bool hasAttribute(const std::string &name) const noexcept
check whether this primitive has a specific attribute
Definition: Primitive.h:99
p
BasicPoint p
Definition: LineStringGeometry.cpp:196
lanelet::RoleName
RoleName
Typical role names within lanelet (for faster lookup)
Definition: primitives/RegulatoryElement.h:55
lanelet::ConstPrimitive< RegulatoryElementData >::attribute
const Attribute & attribute(const std::string &name) const
retrieve an attribute
Definition: Primitive.h:113
lanelet::TrafficLight::removeStopLine
void removeStopLine()
Deletes the stop line.
Definition: BasicRegulatoryElements.cpp:203
lanelet::TrafficSign::trafficSigns
ConstLineStringsOrPolygons3d trafficSigns() const
returns the traffic signs
Definition: BasicRegulatoryElements.cpp:280
lanelet::regTrafficSign
static RegisterRegulatoryElement< TrafficSign > regTrafficSign
Definition: BasicRegulatoryElements.cpp:157
lanelet::RightOfWay::addYieldLanelet
void addYieldLanelet(const Lanelet &lanelet)
Add yielding lanelet.
Definition: BasicRegulatoryElements.cpp:258
lanelet::AttributeValueString::AllWayStop
static constexpr const char AllWayStop[]
Definition: Attribute.h:366
lanelet::regAllWayStop
static RegisterRegulatoryElement< AllWayStop > regAllWayStop
Definition: BasicRegulatoryElements.cpp:159
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::AttributeValueString::RightOfWay
static constexpr const char RightOfWay[]
Definition: Attribute.h:365
lanelet::utils::transform
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
lanelet::Attribute::value
const std::string & value() const
gets the value of this attribute
Definition: Attribute.h:96
lanelet::ManeuverType::Unknown
@ Unknown
Lanelet ist not part of relation.
lanelet::RegulatoryElement::size
size_t size() const
get the number of roles in this regulatoryElement
Definition: primitives/RegulatoryElement.h:236
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
id
Id id
Definition: LaneletMap.cpp:63
lanelet::regTraffic
static RegisterRegulatoryElement< TrafficLight > regTraffic
Definition: BasicRegulatoryElements.cpp:155
lanelet::TrafficSign
Expresses a generic traffic sign rule.
Definition: BasicRegulatoryElements.h:230
lanelet::RuleParameters
std::vector< RuleParameter > RuleParameters
Multiple parameters can have the same role in a rule (eg traffic_lights)
Definition: primitives/RegulatoryElement.h:121
lanelet::AttributeValueString::RegulatoryElement
static constexpr const char RegulatoryElement[]
Definition: Attribute.h:277
lanelet::regSpeedLimit
static RegisterRegulatoryElement< SpeedLimit > regSpeedLimit
Definition: BasicRegulatoryElements.cpp:158
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::LineStringOrPolygon3d::asRuleParameter
RuleParameter asRuleParameter() const
Definition: LineStringOrPolygon.h:91
lanelet::HybridMap::find
iterator find(const key_type &k)
Definition: HybridMap.h:114
lanelet::RoleNameString::Refers
static constexpr const char Refers[]
Definition: primitives/RegulatoryElement.h:66
lanelet::AttributeValueString::TrafficLight
static constexpr const char TrafficLight[]
Definition: Attribute.h:362
lanelet::AllWayStop::addTrafficSign
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
Definition: BasicRegulatoryElements.cpp:409
lanelet::utils::strong
auto strong(std::vector< WeakT > v)
transforms a vector of weak_ptrs to a vector of shared_ptrs
Definition: Utilities.h:347
lanelet::TrafficSign::cancellingTrafficSigns
ConstLineStringsOrPolygons3d cancellingTrafficSigns() const
get list of cancellingTrafficSigns, if existing
Definition: BasicRegulatoryElements.cpp:347
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
Represents a traffic light restriction on the lanelet.
Definition: BasicRegulatoryElements.h:17
lanelet::AttributeName::Type
@ Type
lanelet::TrafficSign::cancelTypes
std::vector< std::string > cancelTypes() const
Types of the cancelling traffic signs if they exist.
Definition: BasicRegulatoryElements.cpp:353
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::RoleNameString::Cancels
static constexpr const char Cancels[]
Definition: primitives/RegulatoryElement.h:70
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::RoleNameString::CancelLine
static constexpr const char CancelLine[]
Definition: primitives/RegulatoryElement.h:71
lanelet::ManeuverType::RightOfWay
@ RightOfWay
Lanelet has right of way
BasicRegulatoryElements.h
lanelet::RegulatoryElement::end
const_iterator end() const
Definition: primitives/RegulatoryElement.h:243
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::LaneletDataConstWptr
std::weak_ptr< const LaneletData > LaneletDataConstWptr
Definition: Forward.h:103
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
Utilities.h
std::operator==
bool operator==(const lanelet::LaneletDataConstWptr &lhs, const lanelet::LaneletDataConstWptr &rhs)
Definition: BasicRegulatoryElements.cpp:12
lanelet::TrafficSignsWithType::trafficSigns
LineStringsOrPolygons3d trafficSigns
Lists relevant traffic signs.
Definition: BasicRegulatoryElements.h:221
lanelet::utils::contains
bool contains(const Container &c, const Value &v)
Definition: Utilities.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::RegulatoryElement::parameters
const RuleParameterMap & parameters() const
Definition: primitives/RegulatoryElement.h:245
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
std
Definition: primitives/Area.h:369
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::RoleName::RightOfWay
@ RightOfWay
A lanelet that has right of way in a relation.
lanelet::TrafficSign::type
std::string type() const
get the id/number of the sign(s)
Definition: BasicRegulatoryElements.cpp:286
RegulatoryElement.h
lanelet::RoleName::CancelLine
@ CancelLine
The line from which a rule is invalidated.
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::LineStringOrPolygon3d
This class holds either a LineString3d or a Polygon3d.
Definition: LineStringOrPolygon.h:86
lanelet::regRightOfWay
static RegisterRegulatoryElement< RightOfWay > regRightOfWay
Definition: BasicRegulatoryElements.cpp:156
lanelet::RoleNameString::Yield
static constexpr const char Yield[]
Definition: primitives/RegulatoryElement.h:68
lanelet::ConstLanelet
An immutable lanelet.
Definition: primitives/Lanelet.h:131
lanelet::RoleNameString::RefLine
static constexpr const char RefLine[]
Definition: primitives/RegulatoryElement.h:67
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
distance
Optional< double > distance
Definition: LineStringGeometry.cpp:168
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
lanelet::AttributeValueString::SpeedLimit
static constexpr const char SpeedLimit[]
Definition: Attribute.h:364
lanelet::RoleName::Refers
@ Refers
The primitive(s) that are the origin of this rule (ie signs)
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::utils::find
auto find(ContainerT &&c, const ValueT &val)
Definition: Utilities.h:186
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::LineString3d
A normal 3d linestring with mutable data.
Definition: primitives/LineString.h:538
lanelet::TrafficLight::addTrafficLight
void addTrafficLight(const LineStringOrPolygon3d &primitive)
add a new traffic light
Definition: BasicRegulatoryElements.cpp:193
lanelet::AttributeName::Subtype
@ Subtype
lanelet::RuleParameter
boost::variant< Point3d, LineString3d, Polygon3d, WeakLanelet, WeakArea > RuleParameter
Definition: primitives/RegulatoryElement.h:90
lanelet::AttributeValueString::TrafficSign
static constexpr const char TrafficSign[]
Definition: Attribute.h:363
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
Definition: Forward.h:114
Exceptions.h
lanelet::RuleParameterMap
HybridMap< RuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map > RuleParameterMap
Rules are stored in a map internally.
Definition: primitives/RegulatoryElement.h:127
lanelet::ManeuverType::Yield
@ Yield
lanelet::TrafficSign::cancelLines
ConstLineStrings3d cancelLines() const
gets the line(s) from which a sign becomes invalid.
Definition: BasicRegulatoryElements.cpp:365
lanelet::InvalidInputError
Thrown when a function was called with invalid input arguments.
Definition: Exceptions.h:56
lanelet::RoleNameString::RightOfWay
static constexpr const char RightOfWay[]
Definition: primitives/RegulatoryElement.h:69


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