Class ConstLanelet

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class ConstLanelet : public lanelet::ConstPrimitive<LaneletData>

An immutable lanelet.

Subclassed by lanelet::Primitive< ConstLanelet >

Public Types

using ConstType = ConstLanelet
using MutableType = Lanelet
using TwoDType = ConstLanelet
using ThreeDType = ConstLanelet
using Category = traits::LaneletTag

Public Functions

inline explicit ConstLanelet(Id id = InvalId)

Constructs an empty or invalid lanelet.

inline 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.

inline explicit ConstLanelet(const std::shared_ptr<const LaneletData> &data, bool inverted = false)

Construct from the data of a different Lanelet.

inline bool inverted() const

returns if this is an inverted lanelet

inline ConstLanelet invert() const

returns the inverted lanelet

inline ConstLineString3d leftBound() const

get the left bound.

inline ConstLineString2d leftBound2d() const

get the left bound in 2d. To be used over leftBound where geometric calculations are required.

inline ConstLineString3d leftBound3d() const

get the left bound in 3d. To be used over leftBound where geometric calculations are required.

inline ConstLineString3d rightBound() const

get the right bound.

inline ConstLineString2d rightBound2d() const

get the right bound in 2d. To be used over rightBound where geometric calculations are required.

inline ConstLineString3d rightBound3d() const

get the right bound in 3d. To be used over rightBound where geometric calculations are required.

inline RegulatoryElementConstPtrs regulatoryElements() const

get a list of regulatory elements that affect this lanelet

template<typename RegElemT>
inline std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const

get the regulatoryElements that could be converted to RegElemT

inline ConstLineString3d centerline() const

get the (cached) centerline of this lanelet.

inline ConstLineString2d centerline2d() const

get the (cached) centerline of this lanelet in 2d. To be used in context of geometric calculations.

inline ConstLineString3d centerline3d() const

get the (cached) centerline of this lanelet in 3d. To be used in context of geometric calculations.

inline bool hasCustomCenterline() const

Returns whether the centerline has been overridden by setCenterline.

CompoundPolygon3d polygon3d() const

returns the surface covered by this lanelet as 3-dimensional polygon.

CompoundPolygon2d polygon2d() const

returns the surface covered by this lanelet as 2-dimensional polygon.

inline void resetCache() const

resets the internal cache of the centerline

this can be necessary if an element of the linestring was modified somewhere else.