Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Private Attributes | List of all members
lanelet::ConstPrimitive< Data > Class Template Reference

Basic Primitive class for all primitives of lanelet2. More...

#include <Primitive.h>

Public Types

using DataType = Data
 

Public Member Functions

const Attributeattribute (AttributeName name) const
 retrieve an attribute (enum version) More...
 
const Attributeattribute (const std::string &name) const
 retrieve an attribute More...
 
template<typename T >
attributeOr (AttributeName name, T defaultVal) const
 retrieve an attribute (enum version) More...
 
template<typename T >
attributeOr (const std::string &name, T defaultVal) const noexcept
 retrieve an attribute (string version) More...
 
const AttributeMapattributes () const
 get the attributes of this primitive More...
 
const std::shared_ptr< const Data > & constData () const
 get the internal data of this primitive More...
 
 ConstPrimitive (const std::shared_ptr< const Data > &data)
 Construct from a pointer to the data. More...
 
bool hasAttribute (AttributeName name) const noexcept
 check for an attribute (enum version) More...
 
bool hasAttribute (const std::string &name) const noexcept
 check whether this primitive has a specific attribute More...
 
Id id () const noexcept
 get the unique id of this primitive More...
 
bool operator!= (const ConstPrimitive &rhs) const
 
bool operator== (const ConstPrimitive &rhs) const
 

Static Public Attributes

static constexpr bool IsConst = true
 

Protected Member Functions

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

Private Attributes

std::shared_ptr< const Data > constData_
 the data this primitive holds More...
 

Detailed Description

template<typename Data>
class lanelet::ConstPrimitive< Data >

Basic Primitive class for all primitives of lanelet2.

Template Parameters
DataType of the data object that this ConstPrimitive holds

Definition at line 70 of file Primitive.h.

Member Typedef Documentation

◆ DataType

template<typename Data >
using lanelet::ConstPrimitive< Data >::DataType = Data

Definition at line 72 of file Primitive.h.

Constructor & Destructor Documentation

◆ ConstPrimitive() [1/3]

template<typename Data >
lanelet::ConstPrimitive< Data >::ConstPrimitive ( const std::shared_ptr< const Data > &  data)
inlineexplicit

Construct from a pointer to the data.

Parameters
datainternal data for this primitive. Must not be null.

Definition at line 78 of file Primitive.h.

◆ ConstPrimitive() [2/3]

template<typename Data >
lanelet::ConstPrimitive< Data >::ConstPrimitive ( ConstPrimitive< Data > &&  rhs)
protecteddefaultnoexcept

◆ ConstPrimitive() [3/3]

template<typename Data >
lanelet::ConstPrimitive< Data >::ConstPrimitive ( const ConstPrimitive< Data > &  rhs)
protecteddefault

◆ ~ConstPrimitive()

template<typename Data >
lanelet::ConstPrimitive< Data >::~ConstPrimitive ( )
protecteddefaultnoexcept

Member Function Documentation

◆ attribute() [1/2]

template<typename Data >
const Attribute& lanelet::ConstPrimitive< Data >::attribute ( AttributeName  name) const
inline

retrieve an attribute (enum version)

Exceptions
NoSuchAttributeErrorif it does not exist

Definition at line 125 of file Primitive.h.

◆ attribute() [2/2]

template<typename Data >
const Attribute& lanelet::ConstPrimitive< Data >::attribute ( const std::string &  name) const
inline

retrieve an attribute

Exceptions
NoSuchAttributeErrorif it does not exist

Definition at line 113 of file Primitive.h.

◆ attributeOr() [1/2]

template<typename Data >
template<typename T >
T lanelet::ConstPrimitive< Data >::attributeOr ( AttributeName  name,
defaultVal 
) const
inline

retrieve an attribute (enum version)

Parameters
namename of the attribute
defaultValvalue returned if not existing
Template Parameters
Treturn type (must be one of Attribute::as<T>())

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

Definition at line 165 of file Primitive.h.

◆ attributeOr() [2/2]

template<typename Data >
template<typename T >
T lanelet::ConstPrimitive< Data >::attributeOr ( const std::string &  name,
defaultVal 
) const
inlinenoexcept

retrieve an attribute (string version)

Parameters
namename of the attribute
defaultValvalue returned if not existing
Template Parameters
Treturn type (must be one of Attribute::as<T>())

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

Definition at line 143 of file Primitive.h.

◆ attributes()

template<typename Data >
const AttributeMap& lanelet::ConstPrimitive< Data >::attributes ( ) const
inline

get the attributes of this primitive

Definition at line 89 of file Primitive.h.

◆ constData()

template<typename Data >
const std::shared_ptr<const Data>& lanelet::ConstPrimitive< Data >::constData ( ) const
inline

get the internal data of this primitive

Definition at line 178 of file Primitive.h.

◆ hasAttribute() [1/2]

template<typename Data >
bool lanelet::ConstPrimitive< Data >::hasAttribute ( AttributeName  name) const
inlinenoexcept

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.

Definition at line 107 of file Primitive.h.

◆ hasAttribute() [2/2]

template<typename Data >
bool lanelet::ConstPrimitive< Data >::hasAttribute ( const std::string &  name) const
inlinenoexcept

check whether this primitive has a specific attribute

Definition at line 99 of file Primitive.h.

◆ id()

template<typename Data >
Id lanelet::ConstPrimitive< Data >::id ( ) const
inlinenoexcept

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.

Definition at line 96 of file Primitive.h.

◆ operator!=()

template<typename Data >
bool lanelet::ConstPrimitive< Data >::operator!= ( const ConstPrimitive< Data > &  rhs) const
inline

Definition at line 86 of file Primitive.h.

◆ operator=() [1/2]

template<typename Data >
ConstPrimitive& lanelet::ConstPrimitive< Data >::operator= ( const ConstPrimitive< Data > &  rhs)
protecteddefault

◆ operator=() [2/2]

template<typename Data >
ConstPrimitive& lanelet::ConstPrimitive< Data >::operator= ( ConstPrimitive< Data > &&  rhs)
protecteddefaultnoexcept

◆ operator==()

template<typename Data >
bool lanelet::ConstPrimitive< Data >::operator== ( const ConstPrimitive< Data > &  rhs) const
inline

Definition at line 85 of file Primitive.h.

Member Data Documentation

◆ constData_

template<typename Data >
std::shared_ptr<const Data> lanelet::ConstPrimitive< Data >::constData_
private

the data this primitive holds

Definition at line 189 of file Primitive.h.

◆ IsConst

template<typename Data >
constexpr bool lanelet::ConstPrimitive< Data >::IsConst = true
staticconstexpr

Definition at line 73 of file Primitive.h.


The documentation for this class was generated from the following file:


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52