Common data management class for all Lanelet-Typed objects. More...
#include <Lanelet.h>

Public Member Functions | |
| ConstLineString3d | centerline () const |
| Returns centerline by computing it, if necessary. Result is cached. More... | |
| bool | hasCustomCenterline () const |
| Returns whether the centerline has been overridden by setCenterline. More... | |
| LaneletData (Id id, LineString3d leftBound, LineString3d rightBound, const AttributeMap &attributes=AttributeMap(), RegulatoryElementPtrs regulatoryElements=RegulatoryElementPtrs()) | |
| Constructs a new, valid LaneletData object. More... | |
| const LineString3d & | leftBound () |
| const ConstLineString3d & | leftBound () const |
| CompoundPolygon3d | polygon () const |
| Get the bounding polygon of this lanelet. Result is cached. More... | |
| RegulatoryElementPtrs & | regulatoryElements () |
| RegulatoryElementConstPtrs | regulatoryElements () const |
| template<typename RegElemT > | |
| std::vector< std::shared_ptr< RegElemT > > | regulatoryElementsAs () |
| template<typename RegElemT > | |
| std::vector< std::shared_ptr< const RegElemT > > | regulatoryElementsAs () const |
| void | resetCache () const |
| call this to indicate that the objects data has been modified. More... | |
| const LineString3d & | rightBound () |
| const ConstLineString3d & | rightBound () const |
| void | setCenterline (const LineString3d ¢erline) |
| Sets a new right bound. Resets all cached data of this object. More... | |
| void | setLeftBound (const LineString3d &bound) |
| Sets a new left bound. Resets all cached data of this object. More... | |
| void | setRightBound (const LineString3d &bound) |
| Sets a new right bound. Resets all cached data of this object. More... | |
Public Member Functions inherited from lanelet::PrimitiveData | |
| PrimitiveData & | operator= (const PrimitiveData &rhs)=default |
| PrimitiveData & | operator= (PrimitiveData &&rhs) noexcept=default |
| PrimitiveData () noexcept=default | |
| PrimitiveData (const PrimitiveData &rhs)=default | |
| PrimitiveData (Id id, AttributeMap attributes=AttributeMap()) | |
| Constructs a PrimitiveData object. More... | |
| PrimitiveData (PrimitiveData &&rhs) noexcept=default | |
Private Attributes | |
| std::shared_ptr< ConstLineString3d > | centerline_ |
| LineString3d | leftBound_ |
| represents the left bound More... | |
| RegulatoryElementPtrs | regulatoryElements_ |
| regulatory elements More... | |
| LineString3d | rightBound_ |
| represents the right bound More... | |
Additional Inherited Members | |
Public Attributes inherited from lanelet::PrimitiveData | |
| AttributeMap | attributes |
| attributes of this primitive More... | |
| Id | id {InvalId} |
| Id of this primitive (unique across one map) More... | |
Protected Member Functions inherited from lanelet::PrimitiveData | |
| ~PrimitiveData ()=default | |
Common data management class for all Lanelet-Typed objects.
Definition at line 22 of file primitives/Lanelet.h.
|
inline |
Constructs a new, valid LaneletData object.
Definition at line 28 of file primitives/Lanelet.h.
| ConstLineString3d lanelet::LaneletData::centerline | ( | ) | const |
Returns centerline by computing it, if necessary. Result is cached.
<
Definition at line 247 of file Lanelet.cpp.
| bool lanelet::LaneletData::hasCustomCenterline | ( | ) | const |
Returns whether the centerline has been overridden by setCenterline.
Definition at line 275 of file Lanelet.cpp.
|
inline |
Definition at line 36 of file primitives/Lanelet.h.
|
inline |
Definition at line 35 of file primitives/Lanelet.h.
| CompoundPolygon3d lanelet::LaneletData::polygon | ( | ) | const |
Get the bounding polygon of this lanelet. Result is cached.
Definition at line 280 of file Lanelet.cpp.
|
inline |
Definition at line 44 of file primitives/Lanelet.h.
|
inline |
Definition at line 41 of file primitives/Lanelet.h.
|
inline |
Definition at line 51 of file primitives/Lanelet.h.
|
inline |
Definition at line 47 of file primitives/Lanelet.h.
| void lanelet::LaneletData::resetCache | ( | ) | const |
call this to indicate that the objects data has been modified.
Definition at line 284 of file Lanelet.cpp.
|
inline |
Definition at line 39 of file primitives/Lanelet.h.
|
inline |
Definition at line 38 of file primitives/Lanelet.h.
| void lanelet::LaneletData::setCenterline | ( | const LineString3d & | centerline | ) |
Sets a new right bound. Resets all cached data of this object.
Definition at line 271 of file Lanelet.cpp.
| void lanelet::LaneletData::setLeftBound | ( | const LineString3d & | bound | ) |
Sets a new left bound. Resets all cached data of this object.
Definition at line 257 of file Lanelet.cpp.
| void lanelet::LaneletData::setRightBound | ( | const LineString3d & | bound | ) |
Sets a new right bound. Resets all cached data of this object.
Definition at line 264 of file Lanelet.cpp.
|
mutableprivate |
Definition at line 82 of file primitives/Lanelet.h.
|
private |
represents the left bound
Definition at line 77 of file primitives/Lanelet.h.
|
private |
regulatory elements
Definition at line 79 of file primitives/Lanelet.h.
|
private |
represents the right bound
Definition at line 78 of file primitives/Lanelet.h.