Template Class ConstPrimitive

Class Documentation

template<typename Data>
class ConstPrimitive

Basic Primitive class for all primitives of lanelet2.

Template Parameters:

Data – Type of the data object that this ConstPrimitive holds

Public Types

using DataType = Data

Public Functions

inline explicit ConstPrimitive(const std::shared_ptr<const Data> &data)

Construct from a pointer to the data.

Parameters:

data – internal data for this primitive. Must not be null.

inline bool operator==(const ConstPrimitive &rhs) const
inline bool operator!=(const ConstPrimitive &rhs) const
inline const AttributeMap &attributes() const

get the attributes of this primitive

inline Id id() const noexcept

get the unique id of this primitive

Keep in mind that the Id can also be InvalId, if the element is a temporary structure that is not a part of the map.

inline bool hasAttribute(const std::string &name) const noexcept

check whether this primitive has a specific attribute

inline bool hasAttribute(AttributeName name) const noexcept

check for an attribute (enum version)

The enum version provides a much more efficient access to the data. It is basically the difference between access via a vector and a std::map lookup. However, this kind of access only works for the most common attribte names.

inline const Attribute &attribute(const std::string &name) const

retrieve an attribute

Throws:

NoSuchAttributeError – if it does not exist

inline const Attribute &attribute(AttributeName name) const

retrieve an attribute (enum version)

Throws:

NoSuchAttributeError – if it does not exist

template<typename T>
inline T attributeOr(const std::string &name, T defaultVal) const noexcept

retrieve an attribute (string version)

T can also be an Optional so that you get an empty optional if the value did not exist or could not be converted.

Parameters:
  • name – name of the attribute

  • defaultVal – value returned if not existing

Template Parameters:

T – return type (must be one of Attribute::as<T>())

template<typename T>
inline T attributeOr(AttributeName name, T defaultVal) const

retrieve an attribute (enum version)

T can also be an Optional so that you get an empty optional if the value did not exist or could not be converted.

Parameters:
  • name – name of the attribute

  • defaultVal – value returned if not existing

Template Parameters:

T – return type (must be one of Attribute::as<T>())

inline const std::shared_ptr<const Data> &constData() const

get the internal data of this primitive

Public Static Attributes

static constexpr bool IsConst = true

Protected Functions

ConstPrimitive(ConstPrimitive &&rhs) noexcept = default
ConstPrimitive &operator=(ConstPrimitive &&rhs) noexcept = default
ConstPrimitive(const ConstPrimitive &rhs) = default
ConstPrimitive &operator=(const ConstPrimitive &rhs) = default
~ConstPrimitive() noexcept = default