Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Friends | List of all members
lanelet::Primitive< DerivedConstPrimitive > Class Template Reference

Base class for all mutable Primitives of lanelet2. More...

#include <Primitive.h>

Inheritance diagram for lanelet::Primitive< DerivedConstPrimitive >:
Inheritance graph
[legend]

Public Types

using DataType = typename DerivedConstPrimitive::DataType
 

Public Member Functions

AttributeMapattributes () noexcept
 get the attributes in a mutable way More...
 
 Primitive ()=default
 
template<typename OtherT >
 Primitive (const Primitive< OtherT > &rhs)
 Construct from another primitive. Only works if both share the same. More...
 
 Primitive (const std::shared_ptr< const DataType > &)=delete
 
 Primitive (const std::shared_ptr< DataType > &data)
 Construct a new primitive from shared_ptr to its data. More...
 
void setAttribute (AttributeName name, const Attribute &attribute)
 set or overwrite an attribute (enum version) More...
 
void setAttribute (const std::string &name, const Attribute &attribute)
 set or overwrite an attribute More...
 
void setId (Id id) noexcept
 set a new id for this primitive More...
 

Static Public Attributes

static constexpr bool IsConst = false
 

Protected Member Functions

std::shared_ptr< DataTypedata () const
 
Primitiveoperator= (const Primitive &rhs) noexcept
 
Primitiveoperator= (Primitive &&rhs) noexcept
 
 Primitive (const Primitive &rhs) noexcept
 
 Primitive (Primitive &&rhs) noexcept
 
 ~Primitive () noexcept=default
 

Friends

template<typename >
class Primitive
 

Detailed Description

template<typename DerivedConstPrimitive>
class lanelet::Primitive< DerivedConstPrimitive >

Base class for all mutable Primitives of lanelet2.

Template Parameters
DerivedConstPrimitivethe ConstPrimitive class that this class derives from

Definition at line 243 of file Primitive.h.

Member Typedef Documentation

◆ DataType

template<typename DerivedConstPrimitive >
using lanelet::Primitive< DerivedConstPrimitive >::DataType = typename DerivedConstPrimitive::DataType

Definition at line 246 of file Primitive.h.

Constructor & Destructor Documentation

◆ Primitive() [1/6]

template<typename DerivedConstPrimitive >
lanelet::Primitive< DerivedConstPrimitive >::Primitive ( )
default

◆ Primitive() [2/6]

template<typename DerivedConstPrimitive >
lanelet::Primitive< DerivedConstPrimitive >::Primitive ( const std::shared_ptr< const DataType > &  )
delete

◆ Primitive() [3/6]

template<typename DerivedConstPrimitive >
lanelet::Primitive< DerivedConstPrimitive >::Primitive ( const std::shared_ptr< DataType > &  data)
inlineexplicit

Construct a new primitive from shared_ptr to its data.

Definition at line 254 of file Primitive.h.

◆ Primitive() [4/6]

template<typename DerivedConstPrimitive >
template<typename OtherT >
lanelet::Primitive< DerivedConstPrimitive >::Primitive ( const Primitive< OtherT > &  rhs)
inlineexplicit

Construct from another primitive. Only works if both share the same.

Definition at line 262 of file Primitive.h.

◆ Primitive() [5/6]

template<typename DerivedConstPrimitive >
lanelet::Primitive< DerivedConstPrimitive >::Primitive ( Primitive< DerivedConstPrimitive > &&  rhs)
protecteddefaultnoexcept

◆ Primitive() [6/6]

template<typename DerivedConstPrimitive >
lanelet::Primitive< DerivedConstPrimitive >::Primitive ( const Primitive< DerivedConstPrimitive > &  rhs)
protecteddefaultnoexcept

◆ ~Primitive()

template<typename DerivedConstPrimitive >
lanelet::Primitive< DerivedConstPrimitive >::~Primitive ( )
protecteddefaultnoexcept

Member Function Documentation

◆ attributes()

template<typename DerivedConstPrimitive >
AttributeMap& lanelet::Primitive< DerivedConstPrimitive >::attributes ( )
inlinenoexcept

get the attributes in a mutable way

Definition at line 284 of file Primitive.h.

◆ data()

template<typename DerivedConstPrimitive >
std::shared_ptr<DataType> lanelet::Primitive< DerivedConstPrimitive >::data ( ) const
inlineprotected

Definition at line 287 of file Primitive.h.

◆ operator=() [1/2]

template<typename DerivedConstPrimitive >
Primitive< DerivedConstPrimitive > & lanelet::Primitive< DerivedConstPrimitive >::operator= ( const Primitive< DerivedConstPrimitive > &  rhs)
protecteddefaultnoexcept

◆ operator=() [2/2]

template<typename DerivedConstPrimitive >
Primitive< DerivedConstPrimitive > & lanelet::Primitive< DerivedConstPrimitive >::operator= ( Primitive< DerivedConstPrimitive > &&  rhs)
protecteddefaultnoexcept

◆ setAttribute() [1/2]

template<typename DerivedConstPrimitive >
void lanelet::Primitive< DerivedConstPrimitive >::setAttribute ( AttributeName  name,
const Attribute attribute 
)
inline

set or overwrite an attribute (enum version)

Definition at line 276 of file Primitive.h.

◆ setAttribute() [2/2]

template<typename DerivedConstPrimitive >
void lanelet::Primitive< DerivedConstPrimitive >::setAttribute ( const std::string &  name,
const Attribute attribute 
)
inline

set or overwrite an attribute

Definition at line 273 of file Primitive.h.

◆ setId()

template<typename DerivedConstPrimitive >
void lanelet::Primitive< DerivedConstPrimitive >::setId ( Id  id)
inlinenoexcept

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!

Definition at line 270 of file Primitive.h.

Friends And Related Function Documentation

◆ Primitive

template<typename DerivedConstPrimitive >
template<typename >
friend class Primitive
friend

Definition at line 280 of file Primitive.h.

Member Data Documentation

◆ IsConst

template<typename DerivedConstPrimitive >
constexpr bool lanelet::Primitive< DerivedConstPrimitive >::IsConst = false
staticconstexpr

Definition at line 248 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:53