Class Lanelet

Inheritance Relationships

Base Type

Class Documentation

class Lanelet : public lanelet::Primitive<ConstLanelet>

The famous (mutable) lanelet class.

Public Types

using TwoDType = Lanelet
using ThreeDType = Lanelet

Public Functions

Lanelet() = default
Lanelet(const std::shared_ptr<const LaneletData>&, bool inverted) = delete
inline Lanelet(const LaneletDataPtr &data, bool inverted)
inline Lanelet invert() const

non-const version to invert a lanelet

inline LineString3d leftBound()

Get the left bound.

inline LineString2d leftBound2d()

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

inline LineString3d leftBound3d()

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

inline LineString3d rightBound()

Get the right bound.

inline LineString2d rightBound2d()

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

inline LineString3d rightBound3d()

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

inline ConstLineString3d rightBound() const

get the right bound.

inline void setLeftBound(const LineString3d &bound)

Sets a new left bound and resets the cached centerline.

inline void setRightBound(const LineString3d &bound)

Sets a new right bound and resets the cached centerline.

inline void setCenterline(const LineString3d &centerline)

Forcefully set a new centerline. Must have a valid Id.

This overrides the default behaviour where the centerline is automatically calculated by the library. The centerline will not be updated if the bounds of the lanelet are modified.

There is no check whether the centerline is actually valid.

inline const RegulatoryElementPtrs &regulatoryElements()

Return regulatoryElements that affect this lanelet.

inline void addRegulatoryElement(RegulatoryElementPtr regElem)

Add a new regulatory element.

inline bool removeRegulatoryElement(const RegulatoryElementPtr &regElem)

Removes a regulatory element, returns true on success.

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

Get the regulatoryElements that could be converted to RegElemT.

Primitive() = default
Primitive(const std::shared_ptr<const DataType>&) = delete
inline explicit Primitive(const std::shared_ptr<DataType> &data)

Construct a new primitive from shared_ptr to its data.

template<typename OtherT>
inline explicit Primitive(const Primitive<OtherT> &rhs)

Construct from another primitive. Only works if both share the same.

Primitive(Primitive &&rhs) noexcept
Primitive(const Primitive &rhs) noexcept

Friends

friend class ConstWeakLanelet
friend class Primitive