Public Types | Public Member Functions | Friends | List of all members
lanelet::Area Class Reference

Famous Area class that represents a basic area as element of the map. More...

#include <Area.h>

Inheritance diagram for lanelet::Area:
Inheritance graph
[legend]

Public Types

using ThreeDType = Area
 
using TwoDType = Area
 
- Public Types inherited from lanelet::Primitive< ConstArea >
using DataType = typename ConstArea ::DataType
 
- Public Types inherited from lanelet::ConstArea
using Category = traits::AreaTag
 
using ConstType = ConstArea
 
using MutableType = Area
 
using ThreeDType = ConstArea
 
using TwoDType = ConstArea
 
- Public Types inherited from lanelet::ConstPrimitive< AreaData >
using DataType = AreaData
 

Public Member Functions

void addRegulatoryElement (RegulatoryElementPtr regElem)
 adds a new regulatory element More...
 
 Area ()=default
 
 Area (const AreaDataConstPtr &)=delete
 
 Area (const AreaDataPtr &data)
 
const InnerBoundsinnerBounds ()
 Get the linestrings that form the inner bound. More...
 
const LineStrings3douterBound ()
 Get linestrings that form the outer bound. More...
 
 Primitive ()=default
 
 Primitive (const Primitive &rhs) noexcept
 
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...
 
 Primitive (Primitive &&rhs) noexcept
 
const RegulatoryElementPtrsregulatoryElements ()
 return regulatoryElements that affect this area. More...
 
template<typename RegElemT >
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs ()
 get the regulatoryElements that could be converted to RegElemT More...
 
bool removeRegulatoryElement (const RegulatoryElementPtr &regElem)
 removes a regulatory element, returns true on success More...
 
void setInnerBounds (const std::vector< LineStrings3d > &bounds)
 sets a new inner bound and resets the cache More...
 
void setOuterBound (const LineStrings3d &bound)
 Sets a new outer bound and resets the cache. More...
 
- Public Member Functions inherited from lanelet::Primitive< ConstArea >
AttributeMapattributes () noexcept
 get the attributes in a mutable way More...
 
 Primitive ()=default
 
 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...
 
- Public Member Functions inherited from lanelet::ConstArea
BasicPolygonWithHoles2d basicPolygonWithHoles2d () const
 generates a basic polygon in 2d with holes for this area More...
 
BasicPolygonWithHoles3d basicPolygonWithHoles3d () const
 generates a basic polygon in 2d with holes for this area More...
 
 ConstArea (const std::shared_ptr< const AreaData > &data)
 Constructor to construct from the data of a different Area. More...
 
 ConstArea (Id id, const LineStrings3d &outerBound, const InnerBounds &innerBounds=InnerBounds(), const AttributeMap &attributes=AttributeMap(), const RegulatoryElementPtrs &regulatoryElements=RegulatoryElementPtrs())
 Constructs a new area. More...
 
 ConstArea (Id id=InvalId)
 Constructs an empty or invalid area. More...
 
CompoundPolygons3d innerBoundPolygons () const
 get the inner bounds as polygon More...
 
ConstInnerBounds innerBounds () const
 get the linestrings that form the inner bounds More...
 
ConstLineStrings3d outerBound () const
 Get linestrings that form the outer bound. More...
 
CompoundPolygon3d outerBoundPolygon () const
 get the outer bound as polygon More...
 
RegulatoryElementConstPtrs regulatoryElements () const
 get a list of regulatory elements that affect this area More...
 
template<typename RegElemT >
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs () const
 get the regulatoryElements that could be converted to a type More...
 
- Public Member Functions inherited from lanelet::ConstPrimitive< AreaData >
const Attributeattribute (AttributeName name) const
 retrieve an attribute (enum version) More...
 
const Attributeattribute (const std::string &name) const
 retrieve an attribute More...
 
attributeOr (AttributeName name, T defaultVal) const
 retrieve an attribute (enum version) More...
 
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 AreaData > & constData () const
 get the internal data of this primitive More...
 
 ConstPrimitive (const std::shared_ptr< const AreaData > &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
 

Friends

class ConstWeakArea
 
template<typename >
class Primitive
 

Additional Inherited Members

- Static Public Attributes inherited from lanelet::Primitive< ConstArea >
static constexpr bool IsConst
 
- Static Public Attributes inherited from lanelet::ConstPrimitive< AreaData >
static constexpr bool IsConst
 
- Protected Member Functions inherited from lanelet::Primitive< ConstArea >
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
 
- Protected Member Functions inherited from lanelet::ConstPrimitive< AreaData >
 ConstPrimitive (const ConstPrimitive &rhs)=default
 
 ConstPrimitive (ConstPrimitive &&rhs) noexcept=default
 
ConstPrimitiveoperator= (const ConstPrimitive &rhs)=default
 
ConstPrimitiveoperator= (ConstPrimitive &&rhs) noexcept=default
 
 ~ConstPrimitive () noexcept=default
 

Detailed Description

Famous Area class that represents a basic area as element of the map.

Definition at line 206 of file primitives/Area.h.

Member Typedef Documentation

◆ ThreeDType

Definition at line 210 of file primitives/Area.h.

◆ TwoDType

Definition at line 209 of file primitives/Area.h.

Constructor & Destructor Documentation

◆ Area() [1/3]

lanelet::Area::Area ( )
default

◆ Area() [2/3]

lanelet::Area::Area ( const AreaDataConstPtr )
delete

◆ Area() [3/3]

lanelet::Area::Area ( const AreaDataPtr data)
inlineexplicit

Definition at line 214 of file primitives/Area.h.

Member Function Documentation

◆ addRegulatoryElement()

void lanelet::Area::addRegulatoryElement ( RegulatoryElementPtr  regElem)
inline

adds a new regulatory element

Exceptions
nullptrerror if regElem is a nullptr

Definition at line 240 of file primitives/Area.h.

◆ innerBounds()

const InnerBounds& lanelet::Area::innerBounds ( )
inline

Get the linestrings that form the inner bound.

Definition at line 225 of file primitives/Area.h.

◆ outerBound()

const LineStrings3d& lanelet::Area::outerBound ( )
inline

Get linestrings that form the outer bound.

Definition at line 222 of file primitives/Area.h.

◆ Primitive() [1/6]

lanelet::Primitive< DerivedConstPrimitive >::Primitive
default

◆ Primitive() [2/6]

lanelet::Primitive< DerivedConstPrimitive >::Primitive
defaultnoexcept

◆ Primitive() [3/6]

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

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

Definition at line 262 of file Primitive.h.

◆ Primitive() [4/6]

lanelet::Primitive< DerivedConstPrimitive >::Primitive
delete

◆ Primitive() [5/6]

lanelet::Primitive< DerivedConstPrimitive >::Primitive
inlineexplicit

Construct a new primitive from shared_ptr to its data.

Definition at line 254 of file Primitive.h.

◆ Primitive() [6/6]

lanelet::Primitive< DerivedConstPrimitive >::Primitive
defaultnoexcept

◆ regulatoryElements()

const RegulatoryElementPtrs& lanelet::Area::regulatoryElements ( )
inline

return regulatoryElements that affect this area.

Definition at line 234 of file primitives/Area.h.

◆ regulatoryElementsAs()

template<typename RegElemT >
std::vector<std::shared_ptr<RegElemT> > lanelet::Area::regulatoryElementsAs ( )
inline

get the regulatoryElements that could be converted to RegElemT

Definition at line 260 of file primitives/Area.h.

◆ removeRegulatoryElement()

bool lanelet::Area::removeRegulatoryElement ( const RegulatoryElementPtr regElem)
inline

removes a regulatory element, returns true on success

Definition at line 248 of file primitives/Area.h.

◆ setInnerBounds()

void lanelet::Area::setInnerBounds ( const std::vector< LineStrings3d > &  bounds)
inline

sets a new inner bound and resets the cache

Definition at line 231 of file primitives/Area.h.

◆ setOuterBound()

void lanelet::Area::setOuterBound ( const LineStrings3d bound)
inline

Sets a new outer bound and resets the cache.

Definition at line 228 of file primitives/Area.h.

Friends And Related Function Documentation

◆ ConstWeakArea

friend class ConstWeakArea
friend

Definition at line 211 of file primitives/Area.h.

◆ Primitive

template<typename >
friend class Primitive ( typename  )
friend

Definition at line 280 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