Class LaneletData

Inheritance Relationships

Base Type

Class Documentation

class LaneletData : public lanelet::PrimitiveData

Common data management class for all Lanelet-Typed objects.

Public Functions

inline LaneletData(Id id, LineString3d leftBound, LineString3d rightBound, const AttributeMap &attributes = AttributeMap(), RegulatoryElementPtrs regulatoryElements = RegulatoryElementPtrs())

Constructs a new, valid LaneletData object.

inline const ConstLineString3d &leftBound() const
inline const LineString3d &leftBound()
inline const ConstLineString3d &rightBound() const
inline const LineString3d &rightBound()
inline RegulatoryElementConstPtrs regulatoryElements() const
inline RegulatoryElementPtrs &regulatoryElements()
template<typename RegElemT>
inline std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const
template<typename RegElemT>
inline std::vector<std::shared_ptr<RegElemT>> regulatoryElementsAs()
void setLeftBound(const LineString3d &bound)

Sets a new left bound. Resets all cached data of this object.

void setRightBound(const LineString3d &bound)

Sets a new right bound. Resets all cached data of this object.

void setCenterline(const LineString3d &centerline)

Sets a new right bound. Resets all cached data of this object.

bool hasCustomCenterline() const

Returns whether the centerline has been overridden by setCenterline.

void resetCache() const

call this to indicate that the objects data has been modified.

ConstLineString3d centerline() const

Returns centerline by computing it, if necessary. Result is cached.

CompoundPolygon3d polygon() const

Get the bounding polygon of this lanelet. Result is cached.