primitives/Lanelet.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; c-basic-offset: 2;
2 // indent-tabs-mode: nil -*-
3 
4 #pragma once
5 
6 #include <functional>
7 #include <memory>
8 #include <utility>
9 
10 #include "lanelet2_core/Forward.h"
14 
15 namespace lanelet {
17 
22 class LaneletData : public PrimitiveData {
23  public:
31  leftBound_{std::move(leftBound)},
32  rightBound_{std::move(rightBound)},
34 
35  const ConstLineString3d& leftBound() const { return leftBound_; }
36  const LineString3d& leftBound() { return leftBound_; }
37 
38  const ConstLineString3d& rightBound() const { return rightBound_; }
39  const LineString3d& rightBound() { return rightBound_; }
40 
42  return utils::transform(regulatoryElements_, [](const auto& elem) { return RegulatoryElementConstPtr(elem); });
43  }
45 
46  template <typename RegElemT>
47  std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const {
48  return utils::transformSharedPtr<const RegElemT>(regulatoryElements_);
49  }
50  template <typename RegElemT>
51  std::vector<std::shared_ptr<RegElemT>> regulatoryElementsAs() {
52  return utils::transformSharedPtr<RegElemT>(regulatoryElements_);
53  }
54 
56  void setLeftBound(const LineString3d& bound);
57 
59  void setRightBound(const LineString3d& bound);
60 
63 
65  bool hasCustomCenterline() const;
66 
68  void resetCache() const;
69 
72 
74  CompoundPolygon3d polygon() const;
75 
76  private:
80 
81  // Cached data
82  mutable std::shared_ptr<ConstLineString3d> centerline_;
83 };
84 
128 class ConstLanelet : public ConstPrimitive<LaneletData> {
132  public:
138 
140  explicit ConstLanelet(Id id = InvalId)
141  : ConstLanelet(std::make_shared<LaneletData>(id, LineString3d(), LineString3d()), false) {}
142 
147  : ConstPrimitive{std::make_shared<LaneletData>(id, leftBound, rightBound, attributes, regulatoryElements)} {}
148 
150  explicit ConstLanelet(const std::shared_ptr<const LaneletData>& data, bool inverted = false)
152 
154  bool inverted() const { return inverted_; }
155 
157  ConstLanelet invert() const { return ConstLanelet{constData(), !inverted()}; }
158 
165  return inverted() ? constData()->rightBound().invert() : constData()->leftBound();
166  }
167 
174  return inverted() ? constData()->leftBound().invert() : constData()->rightBound();
175  }
176 
178  RegulatoryElementConstPtrs regulatoryElements() const { return constData()->regulatoryElements(); }
179 
181  template <typename RegElemT>
182  std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const {
183  return constData()->regulatoryElementsAs<RegElemT>();
184  }
185 
188 
191 
194  return inverted() ? constData()->centerline().invert() : constData()->centerline();
195  }
196 
198  bool hasCustomCenterline() const { return constData()->hasCustomCenterline(); }
199 
202 
205 
212  void resetCache() const { constData()->resetCache(); }
213 
214  private:
215  bool inverted_{false};
216 };
217 
221 class Lanelet : public Primitive<ConstLanelet> {
222  public:
223  using Primitive::Primitive;
224  using TwoDType = Lanelet;
226  friend class ConstWeakLanelet;
227  Lanelet() = default;
228  Lanelet(const std::shared_ptr<const LaneletData>&, bool inverted) = delete;
230 
232  Lanelet invert() const { return Lanelet{data(), !inverted()}; }
233 
234  using Primitive::leftBound;
235  using Primitive::leftBound2d;
236  using Primitive::leftBound3d;
239 
242 
244  LineString3d leftBound3d() { return inverted() ? data()->rightBound().invert() : data()->leftBound(); }
245 
246  using Primitive::rightBound;
247  using Primitive::rightBound2d;
248  using Primitive::rightBound3d;
251 
254 
256  LineString3d rightBound3d() { return inverted() ? data()->leftBound().invert() : data()->rightBound(); }
257 
260 
262  void setLeftBound(const LineString3d& bound) {
263  inverted() ? data()->setRightBound(bound.invert()) : data()->setLeftBound(bound);
264  }
265 
267  void setRightBound(const LineString3d& bound) {
268  inverted() ? data()->setLeftBound(bound.invert()) : data()->setRightBound(bound);
269  }
270 
279  inverted() ? data()->setCenterline(centerline.invert()) : data()->setCenterline(centerline);
280  }
281 
283  const RegulatoryElementPtrs& regulatoryElements() { return data()->regulatoryElements(); }
284 
287  if (regElem == nullptr) {
288  throw NullptrError("regulatory element is a nullptr.");
289  }
290  data()->regulatoryElements().push_back(std::move(regElem));
291  }
292 
295  auto& regElems = data()->regulatoryElements();
296  auto remove = std::find(regElems.begin(), regElems.end(), regElem);
297  if (remove != regElems.end()) {
298  regElems.erase(remove);
299  return true;
300  }
301  return false;
302  }
303 
304  using Primitive::regulatoryElements;
305  using Primitive::regulatoryElementsAs;
306 
308  template <typename RegElemT>
309  std::vector<std::shared_ptr<RegElemT>> regulatoryElementsAs() {
310  return data()->regulatoryElementsAs<RegElemT>();
311  }
312 };
313 
317  public:
322  ConstWeakLanelet() = default;
323  ConstWeakLanelet(const ConstLanelet& llet) // NOLINT
324  : laneletData_{llet.constData()}, inverted_{llet.inverted()} {}
325 
330  ConstLanelet lock() const { return ConstLanelet(laneletData_.lock(), inverted_); }
331 
333  bool expired() const noexcept { return laneletData_.expired(); }
334 
335  protected:
336  std::weak_ptr<const LaneletData> laneletData_; // NOLINT
337  bool inverted_{false}; // NOLINT
338 };
339 
342 class WeakLanelet final : public ConstWeakLanelet {
343  public:
344  WeakLanelet() = default;
345  WeakLanelet(const Lanelet& llet) : ConstWeakLanelet(llet) {} // NOLINT
346 
351  Lanelet lock() const { return Lanelet(std::const_pointer_cast<LaneletData>(laneletData_.lock()), inverted_); }
352 };
353 
354 namespace utils {
366 bool has(const ConstLanelet& ll, Id id);
367 } // namespace utils
368 
369 inline bool operator==(const ConstLanelet& lhs, const ConstLanelet& rhs) {
370  return lhs.constData() == rhs.constData() && lhs.inverted() == rhs.inverted();
371 }
372 inline bool operator!=(const ConstLanelet& lhs, const ConstLanelet& rhs) { return !(lhs == rhs); }
373 inline bool operator==(const ConstWeakLanelet& lhs, const ConstWeakLanelet& rhs) {
374  return !lhs.expired() && !rhs.expired() && lhs.lock() == rhs.lock();
375 }
376 inline bool operator!=(const ConstWeakLanelet& lhs, const ConstWeakLanelet& rhs) { return !(lhs == rhs); }
377 std::ostream& operator<<(std::ostream& stream, const ConstLanelet& obj);
378 
379 namespace traits {
380 template <typename T>
381 constexpr bool isLaneletT() {
382  return isCategory<T, traits::LaneletTag>();
383 }
384 } // namespace traits
385 
386 template <typename T, typename RetT>
387 using IfLL = std::enable_if_t<traits::isLaneletT<T>(), RetT>;
388 
389 } // namespace lanelet
390 
391 // Hash function for usage in containers
392 namespace std {
393 template <>
394 struct hash<lanelet::Lanelet> : public lanelet::HashBase<lanelet::Lanelet> {};
395 template <>
396 struct hash<lanelet::ConstLanelet> : public lanelet::HashBase<lanelet::ConstLanelet> {};
397 
398 template <typename T, typename U>
399 struct hash<std::pair<U, T>> {
400  size_t operator()(const std::pair<U, T> x) const noexcept {
401  return std::hash<U>()(x.first) ^ std::hash<T>()(x.second);
402  }
403 };
404 
405 } // namespace std
lanelet::WeakLanelet::WeakLanelet
WeakLanelet(const Lanelet &llet)
Definition: primitives/Lanelet.h:345
lanelet::InvalId
constexpr Id InvalId
indicates a primitive that is not part of a map
Definition: Forward.h:199
lanelet::Lanelet::removeRegulatoryElement
bool removeRegulatoryElement(const RegulatoryElementPtr &regElem)
Removes a regulatory element, returns true on success.
Definition: primitives/Lanelet.h:294
lanelet::HashBase
Definition: Primitive.h:328
lanelet::Primitive
Base class for all mutable Primitives of lanelet2.
Definition: Primitive.h:243
lanelet::LaneletData::regulatoryElements_
RegulatoryElementPtrs regulatoryElements_
regulatory elements
Definition: primitives/Lanelet.h:79
Optional.h
lanelet::Lanelet::leftBound3d
LineString3d leftBound3d()
get the left bound in 3d. To be used over leftBound where geometric calculations are required.
Definition: primitives/Lanelet.h:244
lanelet::RegulatoryElementPtrs
std::vector< RegulatoryElementPtr > RegulatoryElementPtrs
Definition: Forward.h:193
lanelet::ConstWeakLanelet::ConstWeakLanelet
ConstWeakLanelet()=default
lanelet::LaneletData::resetCache
void resetCache() const
call this to indicate that the objects data has been modified.
Definition: Lanelet.cpp:284
lanelet::Lanelet::invert
Lanelet invert() const
non-const version to invert a lanelet
Definition: primitives/Lanelet.h:232
lanelet::PrimitiveData
Common data class for all lanelet primitives.
Definition: Primitive.h:31
lanelet::ConstWeakLanelet::inverted_
bool inverted_
Definition: primitives/Lanelet.h:337
lanelet::LaneletData
Common data management class for all Lanelet-Typed objects.
Definition: primitives/Lanelet.h:22
lanelet::CompoundPolygon3d
Combines multiple linestrings to one polygon in 3d.
Definition: CompoundPolygon.h:40
lanelet::ConstLanelet::centerline2d
ConstLineString2d centerline2d() const
get the (cached) centerline of this lanelet in 2d. To be used in context of geometric calculations.
Definition: primitives/Lanelet.h:190
lanelet::Lanelet::rightBound3d
LineString3d rightBound3d()
get the right bound in 3d. To be used over rightBound where geometric calculations are required.
Definition: primitives/Lanelet.h:256
lanelet::traits::to2D
BoundingBox2d to2D(const BoundingBox3d &primitive)
Definition: primitives/BoundingBox.h:304
lanelet::ConstLanelet::leftBound2d
ConstLineString2d leftBound2d() const
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
Definition: primitives/Lanelet.h:162
lanelet
Definition: Attribute.h:13
lanelet::ConstLanelet::hasCustomCenterline
bool hasCustomCenterline() const
Returns whether the centerline has been overridden by setCenterline.
Definition: primitives/Lanelet.h:198
lanelet::IfLL
std::enable_if_t< traits::isLaneletT< T >(), RetT > IfLL
Definition: primitives/Lanelet.h:387
lanelet::ConstLanelet::rightBound3d
ConstLineString3d rightBound3d() const
get the right bound in 3d. To be used over rightBound where geometric calculations are required.
Definition: primitives/Lanelet.h:173
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
Definition: Forward.h:192
lanelet::ConstLanelet::invert
ConstLanelet invert() const
returns the inverted lanelet
Definition: primitives/Lanelet.h:157
lanelet::ConstPrimitive< LaneletData >::attributes
const AttributeMap & attributes() const
get the attributes of this primitive
Definition: Primitive.h:89
lanelet::ConstLanelet::centerline
ConstLineString3d centerline() const
get the (cached) centerline of this lanelet.
Definition: primitives/Lanelet.h:187
lanelet::Lanelet::regulatoryElements
const RegulatoryElementPtrs & regulatoryElements()
Return regulatoryElements that affect this lanelet.
Definition: primitives/Lanelet.h:283
lanelet::Lanelet::setCenterline
void setCenterline(const LineString3d &centerline)
Definition: primitives/Lanelet.h:278
lanelet::AttributeMap
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
Definition: Attribute.h:371
lanelet::ConstLanelet::rightBound2d
ConstLineString2d rightBound2d() const
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
Definition: primitives/Lanelet.h:171
lanelet::ConstLanelet::inverted
bool inverted() const
returns if this is an inverted lanelet
Definition: primitives/Lanelet.h:154
lanelet::LaneletData::rightBound_
LineString3d rightBound_
represents the right bound
Definition: primitives/Lanelet.h:78
lanelet::Lanelet::rightBound2d
LineString2d rightBound2d()
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
Definition: primitives/Lanelet.h:253
lanelet::operator==
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
lanelet::ConstLanelet::inverted_
bool inverted_
indicates if this lanelet is inverted
Definition: primitives/Lanelet.h:215
lanelet::Id
int64_t Id
Definition: Forward.h:198
lanelet::operator<<
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
std::hash< std::pair< U, T > >::operator()
size_t operator()(const std::pair< U, T > x) const noexcept
Definition: primitives/Lanelet.h:400
lanelet::LaneletData::setLeftBound
void setLeftBound(const LineString3d &bound)
Sets a new left bound. Resets all cached data of this object.
Definition: Lanelet.cpp:257
lanelet::utils::transform
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
lanelet::ConstWeakLanelet::laneletData_
std::weak_ptr< const LaneletData > laneletData_
Definition: primitives/Lanelet.h:336
lanelet::WeakLanelet::lock
Lanelet lock() const
Obtains the original Lanelet.
Definition: primitives/Lanelet.h:351
lanelet::Lanelet::setRightBound
void setRightBound(const LineString3d &bound)
Sets a new right bound and resets the cached centerline.
Definition: primitives/Lanelet.h:267
lanelet::ConstLanelet::regulatoryElements
RegulatoryElementConstPtrs regulatoryElements() const
get a list of regulatory elements that affect this lanelet
Definition: primitives/Lanelet.h:178
lanelet::LaneletData::regulatoryElements
RegulatoryElementConstPtrs regulatoryElements() const
Definition: primitives/Lanelet.h:41
lanelet::LaneletData::hasCustomCenterline
bool hasCustomCenterline() const
Returns whether the centerline has been overridden by setCenterline.
Definition: Lanelet.cpp:275
lanelet::ConstLineString2d
A normal 2d linestring with immutable data.
Definition: primitives/LineString.h:552
lanelet::ConstLanelet::resetCache
void resetCache() const
resets the internal cache of the centerline
Definition: primitives/Lanelet.h:212
lanelet::LineString2d
A normal 2d linestring with mutable data.
Definition: primitives/LineString.h:569
lanelet::ConstPrimitive< LaneletData >::constData
const std::shared_ptr< const LaneletData > & constData() const
get the internal data of this primitive
Definition: Primitive.h:178
lanelet::LaneletType
LaneletType
Definition: primitives/Lanelet.h:16
Primitive.h
lanelet::Lanelet::rightBound
ConstLineString3d rightBound() const
get the right bound.
Definition: primitives/Lanelet.h:259
lanelet::Lanelet
The famous (mutable) lanelet class.
Definition: primitives/Lanelet.h:221
lanelet::ConstWeakLanelet::expired
bool expired() const noexcept
tests whether the WeakLanelet is still valid
Definition: primitives/Lanelet.h:333
lanelet::LaneletData::rightBound
const LineString3d & rightBound()
Definition: primitives/Lanelet.h:39
lanelet::LaneletData::centerline_
std::shared_ptr< ConstLineString3d > centerline_
Definition: primitives/Lanelet.h:82
lanelet::WeakLanelet
Definition: primitives/Lanelet.h:342
lanelet::ConstWeakLanelet::ConstWeakLanelet
ConstWeakLanelet(const ConstLanelet &llet)
Definition: primitives/Lanelet.h:323
lanelet::PrimitiveData::attributes
AttributeMap attributes
attributes of this primitive
Definition: Primitive.h:45
lanelet::ConstLanelet::ConstLanelet
ConstLanelet(Id id=InvalId)
Constructs an empty or invalid lanelet.
Definition: primitives/Lanelet.h:140
lanelet::Lanelet::Lanelet
Lanelet(const LaneletDataPtr &data, bool inverted)
Definition: primitives/Lanelet.h:229
lanelet::LaneletType::Bidirectional
@ Bidirectional
lanelet::ConstLanelet::polygon2d
CompoundPolygon2d polygon2d() const
returns the surface covered by this lanelet as 2-dimensional polygon.
Definition: Lanelet.cpp:316
lanelet::Primitive::Primitive
friend class Primitive
Definition: Primitive.h:280
lanelet::LineString3d::invert
LineString3d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:546
lanelet::ConstWeakLanelet::lock
ConstLanelet lock() const
Obtains the original ConstLanelet.
Definition: primitives/Lanelet.h:330
lanelet::ConstLineString3d::invert
ConstLineString3d invert() const noexcept
create a new, inverted linestring from this one
Definition: primitives/LineString.h:532
lanelet::CompoundPolygon2d
Combines multiple linestrings to one polygon in 2d.
Definition: CompoundPolygon.h:11
lanelet::operator!=
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
lanelet::ConstLanelet::leftBound3d
ConstLineString3d leftBound3d() const
get the left bound in 3d. To be used over leftBound where geometric calculations are required.
Definition: primitives/Lanelet.h:164
lanelet::LaneletData::centerline
ConstLineString3d centerline() const
Returns centerline by computing it, if necessary. Result is cached.
Definition: Lanelet.cpp:247
lanelet::Lanelet::Lanelet
Lanelet()=default
lanelet::LaneletType::OneWay
@ OneWay
lanelet::LaneletData::setRightBound
void setRightBound(const LineString3d &bound)
Sets a new right bound. Resets all cached data of this object.
Definition: Lanelet.cpp:264
lanelet::ConstLanelet::regulatoryElementsAs
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
get the regulatoryElements that could be converted to RegElemT
Definition: primitives/Lanelet.h:182
lanelet::Lanelet::addRegulatoryElement
void addRegulatoryElement(RegulatoryElementPtr regElem)
Add a new regulatory element.
Definition: primitives/Lanelet.h:286
lanelet::Lanelet::setLeftBound
void setLeftBound(const LineString3d &bound)
Sets a new left bound and resets the cached centerline.
Definition: primitives/Lanelet.h:262
lanelet::RegulatoryElementConstPtr
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
Definition: Forward.h:194
lanelet::traits::isLaneletT
constexpr bool isLaneletT()
Definition: primitives/Lanelet.h:381
lanelet::traits::LaneletTag
Identifies PolygonPrimitives.
Definition: Traits.h:10
lanelet::Lanelet::rightBound
LineString3d rightBound()
Get the right bound.
Definition: primitives/Lanelet.h:250
lanelet::HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::utils::has
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
Definition: primitives/Area.h:324
lanelet::WeakLanelet::WeakLanelet
WeakLanelet()=default
lanelet::LaneletDataPtr
std::shared_ptr< LaneletData > LaneletDataPtr
Definition: Forward.h:100
lanelet::ConstPrimitive
Basic Primitive class for all primitives of lanelet2.
Definition: Primitive.h:70
std
Definition: primitives/Area.h:369
lanelet::ConstLanelet::centerline3d
ConstLineString3d centerline3d() const
get the (cached) centerline of this lanelet in 3d. To be used in context of geometric calculations.
Definition: primitives/Lanelet.h:193
lanelet::LaneletData::leftBound_
LineString3d leftBound_
represents the left bound
Definition: primitives/Lanelet.h:77
lanelet::Lanelet::leftBound2d
LineString2d leftBound2d()
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
Definition: primitives/Lanelet.h:241
lanelet::RegulatoryElementConstPtrs
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
Definition: Forward.h:195
lanelet::ConstLineString3d
A normal 3d linestring with immutable data.
Definition: primitives/LineString.h:521
lanelet::ConstLanelet::ConstLanelet
ConstLanelet(Id id, const LineString3d &leftBound, const LineString3d &rightBound, const AttributeMap &attributes=AttributeMap(), const RegulatoryElementPtrs &regulatoryElements=RegulatoryElementPtrs())
Constructs a lanelet from id, attributes, regulatoryElements and bounds.
Definition: primitives/Lanelet.h:144
lanelet::LaneletData::regulatoryElementsAs
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
Definition: primitives/Lanelet.h:51
lanelet::ConstLanelet
An immutable lanelet.
Definition: primitives/Lanelet.h:131
LineString.h
lanelet::Lanelet::leftBound
LineString3d leftBound()
Get the left bound.
Definition: primitives/Lanelet.h:238
lanelet::ConstWeakLanelet
Definition: primitives/Lanelet.h:316
lanelet::LaneletData::leftBound
const ConstLineString3d & leftBound() const
Definition: primitives/Lanelet.h:35
lanelet::NullptrError
SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usual...
Definition: Exceptions.h:80
lanelet::PrimitiveData::id
Id id
Id of this primitive (unique across one map)
Definition: Primitive.h:44
Forward.h
lanelet::LaneletData::setCenterline
void setCenterline(const LineString3d &centerline)
Sets a new right bound. Resets all cached data of this object.
Definition: Lanelet.cpp:271
lanelet::ConstLanelet::leftBound
ConstLineString3d leftBound() const
get the left bound.
Definition: primitives/Lanelet.h:160
lanelet::LaneletData::polygon
CompoundPolygon3d polygon() const
Get the bounding polygon of this lanelet. Result is cached.
Definition: Lanelet.cpp:280
lanelet::LaneletData::leftBound
const LineString3d & leftBound()
Definition: primitives/Lanelet.h:36
lanelet::Primitive< ConstLanelet >::data
std::shared_ptr< DataType > data() const
Definition: Primitive.h:287
lanelet::utils::find
auto find(ContainerT &&c, const ValueT &val)
Definition: Utilities.h:186
lanelet::LaneletData::rightBound
const ConstLineString3d & rightBound() const
Definition: primitives/Lanelet.h:38
lanelet::LaneletData::regulatoryElementsAs
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
Definition: primitives/Lanelet.h:47
lanelet::LineString3d
A normal 3d linestring with mutable data.
Definition: primitives/LineString.h:538
lanelet::ConstLanelet::ConstLanelet
ConstLanelet(const std::shared_ptr< const LaneletData > &data, bool inverted=false)
Construct from the data of a different Lanelet.
Definition: primitives/Lanelet.h:150
lanelet::ConstPrimitive< LaneletData >::id
Id id() const noexcept
get the unique id of this primitive
Definition: Primitive.h:96
lanelet::ConstLanelet::polygon3d
CompoundPolygon3d polygon3d() const
returns the surface covered by this lanelet as 3-dimensional polygon.
Definition: Lanelet.cpp:314
lanelet::ConstLanelet::rightBound
ConstLineString3d rightBound() const
get the right bound.
Definition: primitives/Lanelet.h:169
lanelet::LaneletData::LaneletData
LaneletData(Id id, LineString3d leftBound, LineString3d rightBound, const AttributeMap &attributes=AttributeMap(), RegulatoryElementPtrs regulatoryElements=RegulatoryElementPtrs())
Constructs a new, valid LaneletData object.
Definition: primitives/Lanelet.h:28
lanelet::Lanelet::regulatoryElementsAs
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
Get the regulatoryElements that could be converted to RegElemT.
Definition: primitives/Lanelet.h:309
lanelet::LaneletData::regulatoryElements
RegulatoryElementPtrs & regulatoryElements()
Definition: primitives/Lanelet.h:44


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