69 template <
typename Data>
73 static constexpr
bool IsConst =
true;
78 explicit ConstPrimitive(
const std::shared_ptr<const Data>& data) : constData_{data} {
96 Id id() const noexcept {
return constData_->
id; }
116 }
catch (std::out_of_range& err) {
128 }
catch (std::out_of_range& err) {
142 template <
typename T>
143 T
attributeOr(
const std::string& name, T defaultVal)
const noexcept {
148 auto val = elem->second.template as<T>();
164 template <
typename T>
170 auto val = elem->second.template as<T>();
178 const std::shared_ptr<const Data>&
constData()
const {
return constData_; }
242 template <
typename DerivedConstPrimitive>
246 using DataType =
typename DerivedConstPrimitive::DataType;
247 using DerivedConstPrimitive::DerivedConstPrimitive;
248 static constexpr
bool IsConst =
false;
251 Primitive(
const std::shared_ptr<const DataType>&) =
delete;
254 explicit Primitive(
const std::shared_ptr<DataType>& data) : DerivedConstPrimitive(data) {
261 template <
typename OtherT>
282 using DerivedConstPrimitive::attributes;
287 std::shared_ptr<DataType>
data()
const {
290 return std::const_pointer_cast<
DataType>(this->constData());
304 template <
typename PrimitiveT>
306 template <
typename PrimitiveT>
309 template <
typename DataT>
314 template <
typename NotPrimitive>
320 template <
typename PrimitiveT>
322 PrimitiveT* v =
nullptr;
323 return IsLaneletPrimitiveHelper(v, 0);
327 template <
typename PrimitiveT>
329 size_t operator()(
const PrimitiveT& x)
const noexcept {
return std::hash<Id>()(x.id()); }
332 template <
typename DerivedConstPrimitive>
335 template <
typename DerivedConstPrimitive>
338 template <
typename DerivedConstPrimitive>
341 template <
typename DerivedConstPrimitive>
Id id() const noexcept
get the unique id of this primitive
bool hasAttribute(const std::string &name) const noexcept
check whether this primitive has a specific attribute
AttributeMap attributes
attributes of this primitive
Primitive(const Primitive< OtherT > &rhs)
Construct from another primitive. Only works if both share the same.
PrimitiveData(Id id, AttributeMap attributes=AttributeMap())
Constructs a PrimitiveData object.
iterator find(const key_type &k)
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
const AttributeMap & attributes() const
get the attributes of this primitive
T attributeOr(const std::string &name, T defaultVal) const noexcept
retrieve an attribute (string version)
T attributeOr(AttributeName name, T defaultVal) const
retrieve an attribute (enum version)
PrimitiveData & operator=(PrimitiveData &&rhs) noexcept=default
const ValueT & at(const key_type &k) const
bool operator==(const ConstPrimitive &rhs) const
const Attribute & attribute(const std::string &name) const
retrieve an attribute
typename ConstLineStringT ::DataType DataType
Primitive & operator=(Primitive &&rhs) noexcept
const std::shared_ptr< const Data > & constData() const
get the internal data of this primitive
void setAttribute(AttributeName name, const Attribute &attribute)
set or overwrite an attribute (enum version)
SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usual...
Basic Primitive class for all primitives of lanelet2.
An attribute represents one value of a tag of a lanelet primitive.
Base class for all mutable Primitives of lanelet2.
std::shared_ptr< const Data > constData_
the data this primitive holds
Common data class for all lanelet primitivesThis class provides the data that all lanelet primitives ...
size_t operator()(const PrimitiveT &x) const noexcept
void setId(Id id) noexcept
set a new id for this primitive
AttributeMap & attributes() noexcept
get the attributes in a mutable way
std::shared_ptr< DataType > data() const
Common data management class for all Area-Typed objects.
bool isLaneletPrimitiveHelper(NotPrimitive *, long)
Thrown when an attribute has been queried that does not exist.
constexpr bool isLaneletPrimitive()
Id id
Id of this primitive (unique across one map)
Primitive(const std::shared_ptr< DataType > &data)
Construct a new primitive from shared_ptr to its data.
ConstPrimitive(const std::shared_ptr< const Data > &data)
Construct from a pointer to the data.
const Attribute & attribute(AttributeName name) const
retrieve an attribute (enum version)
void setAttribute(const std::string &name, const Attribute &attribute)
set or overwrite an attribute
bool hasAttribute(AttributeName name) const noexcept
check for an attribute (enum version)
bool operator!=(const ConstPrimitive &rhs) const
AttributeName
Typical Attributes names within lanelet.
constexpr Id InvalId
indicates a primitive that is not part of a map
PrimitiveData() noexcept=default