Go to the documentation of this file.
69 template <
typename Data>
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>();
242 template <typename DerivedConstPrimitive>
246 using DataType =
typename DerivedConstPrimitive::DataType;
247 using DerivedConstPrimitive::DerivedConstPrimitive;
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>
constexpr Id InvalId
indicates a primitive that is not part of a map
Base class for all mutable Primitives of lanelet2.
An attribute represents one value of a tag of a lanelet primitive.
static constexpr bool IsConst
PrimitiveData(Id id, AttributeMap attributes=AttributeMap())
Constructs a PrimitiveData object.
Primitive(const std::shared_ptr< DataType > &data)
Construct a new primitive from shared_ptr to its data.
Common data class for all lanelet primitives.
T attributeOr(const std::string &name, T defaultVal) const noexcept
retrieve an attribute (string version)
typename ConstLineStringT ::DataType DataType
T attributeOr(AttributeName name, T defaultVal) const
retrieve an attribute (enum version)
const AttributeMap & attributes() const
get the attributes of this primitive
Primitive(const Primitive< OtherT > &rhs)
Construct from another primitive. Only works if both share the same.
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
bool hasAttribute(const std::string &name) const noexcept
check whether this primitive has a specific attribute
const Attribute & attribute(const std::string &name) const
retrieve an attribute
const ValueT & at(const key_type &k) const
AttributeMap & attributes() noexcept
get the attributes in a mutable way
PrimitiveData & operator=(PrimitiveData &&rhs) noexcept=default
iterator find(const key_type &k)
const std::shared_ptr< const Data > & constData() const
get the internal data of this primitive
ConstPrimitive & operator=(ConstPrimitive &&rhs) noexcept=default
constexpr bool isLaneletPrimitive()
AttributeMap attributes
attributes of this primitive
bool operator==(const ConstPrimitive &rhs) const
std::shared_ptr< const Data > constData_
the data this primitive holds
const Attribute & attribute(AttributeName name) const
retrieve an attribute (enum version)
Common data management class for all Area-Typed objects.
size_t operator()(const PrimitiveT &x) const noexcept
Thrown when an attribute has been queried that does not exist.
bool isLaneletPrimitiveHelper(NotPrimitive *, long)
void setAttribute(const std::string &name, const Attribute &attribute)
set or overwrite an attribute
ConstPrimitive(const std::shared_ptr< const Data > &data)
Construct from a pointer to the data.
Basic Primitive class for all primitives of lanelet2.
void setId(Id id) noexcept
set a new id for this primitive
bool hasAttribute(AttributeName name) const noexcept
check for an attribute (enum version)
~ConstPrimitive() noexcept=default
bool operator!=(const ConstPrimitive &rhs) const
AttributeName
Typical Attributes names within lanelet.
SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usual...
void setAttribute(AttributeName name, const Attribute &attribute)
set or overwrite an attribute (enum version)
Id id
Id of this primitive (unique across one map)
PrimitiveData() noexcept=default
std::shared_ptr< DataType > data() const
Id id() const noexcept
get the unique id of this primitive
Primitive & operator=(Primitive &&rhs) noexcept
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52