Template Class Primitive

Inheritance Relationships

Base Type

  • public DerivedConstPrimitive

Derived Types

Class Documentation

template<typename DerivedConstPrimitive>
class Primitive : public DerivedConstPrimitive

Base class for all mutable Primitives of lanelet2.

Template Parameters:

DerivedConstPrimitive – the ConstPrimitive class that this class derives from

Subclassed by lanelet::LineStringImpl< ConstLineString2d >, lanelet::LineStringImpl< ConstLineString3d >, lanelet::LineStringImpl< ConstPolygon2d >, lanelet::LineStringImpl< ConstPolygon3d >

Public Types

using DataType = typename DerivedConstPrimitive::DataType

Public Functions

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.

inline void setId(Id id) noexcept

set a new id for this primitive

This is the best way to corrupt a map, because all primitives are identified by their id. Make sure you know what you are doing!

inline void setAttribute(const std::string &name, const Attribute &attribute)

set or overwrite an attribute

inline void setAttribute(AttributeName name, const Attribute &attribute)

set or overwrite an attribute (enum version)

inline AttributeMap &attributes() noexcept

get the attributes in a mutable way

Public Static Attributes

static constexpr bool IsConst = false

Protected Functions

inline std::shared_ptr<DataType> data() const
Primitive(Primitive &&rhs) noexcept
Primitive &operator=(Primitive &&rhs) noexcept
Primitive(const Primitive &rhs) noexcept
Primitive &operator=(const Primitive &rhs) noexcept
~Primitive() noexcept = default

Friends

friend class Primitive