Public Member Functions | Private Attributes | List of all members
lanelet::LaneletSubmap Class Reference

A LaneletSubmap only contains the elemets that have be expleicitly added to it. More...

#include <LaneletMap.h>

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

Public Member Functions

void add (Area area)
 adds an area More...
 
void add (const RegulatoryElementPtr &regElem)
 adds a new regulatory element to the submap. More...
 
void add (Lanelet lanelet)
 adds a lanelet to the submap More...
 
void add (LineString3d lineString)
 adds a new lineString the submap More...
 
void add (Point3d point)
 adds a new point to the submap More...
 
void add (Polygon3d polygon)
 adds a new polygon to the submap More...
 
LaneletMapUPtr laneletMap ()
 
LaneletMapConstPtr laneletMap () const
 Converts this into a fully valid lanelet map. More...
 
 LaneletMapLayers ()=default
 
 LaneletMapLayers (const LaneletLayer::Map &lanelets, const AreaLayer::Map &areas, const RegulatoryElementLayer::Map &regulatoryElements, const PolygonLayer::Map &polygons, const LineStringLayer::Map &lineStrings, const PointLayer::Map &points)
 Construct from already initialized layers. More...
 
 LaneletMapLayers (const LaneletMapLayers &rhs)=delete
 
 LaneletMapLayers (LaneletMapLayers &&rhs) noexcept=default
 
 LaneletSubmap ()=default
 
 LaneletSubmap (LaneletMap &&rhs) noexcept
 Constructs a submap from a moved-from LaneletMap. More...
 
LaneletSubmapoperator= (LaneletMap &&rhs)
 
void trackParameters (const RegulatoryElement &regelem)
 
- Public Member Functions inherited from lanelet::LaneletMapLayers
bool empty () const noexcept
 Returns whether all layers of this object are empty. More...
 
 LaneletMapLayers ()=default
 
 LaneletMapLayers (const LaneletLayer::Map &lanelets, const AreaLayer::Map &areas, const RegulatoryElementLayer::Map &regulatoryElements, const PolygonLayer::Map &polygons, const LineStringLayer::Map &lineStrings, const PointLayer::Map &points)
 Construct from already initialized layers. More...
 
 LaneletMapLayers (const LaneletMapLayers &rhs)=delete
 
 LaneletMapLayers (LaneletMapLayers &&rhs) noexcept=default
 
LaneletMapLayersoperator= (const LaneletMapLayers &rhs)=delete
 
LaneletMapLayersoperator= (LaneletMapLayers &&rhs) noexcept=default
 
size_t size () const noexcept
 Returns the total number of elements in all layers. More...
 
 ~LaneletMapLayers () noexcept=default
 

Private Attributes

std::vector< boost::variant< ConstLanelet, ConstArea > > regelemObjects_
 In order to not let lanelets/areas referenced by regelems get out of scope, we keep a reference to them here. More...
 

Additional Inherited Members

- Public Attributes inherited from lanelet::LaneletMapLayers
AreaLayer areaLayer
 access to areas More...
 
LaneletLayer laneletLayer
 access to the lanelets within this map More...
 
LineStringLayer lineStringLayer
 access to the lineStrings More...
 
PointLayer pointLayer
 access to the points More...
 
PolygonLayer polygonLayer
 access to the polygons More...
 
RegulatoryElementLayer regulatoryElementLayer
 access to regElems More...
 

Detailed Description

A LaneletSubmap only contains the elemets that have be expleicitly added to it.

This class is similar to a LaneletMap but with one fundamental difference: It is not self-contained. When add is called with an object only this object is added to the map and nothing else like e.g. its subobjects. But you can always convert this object back to a laneletMap by calling "LaneletSubmap::laneletMap", which is of course a costly operation.

If you want to have a function that can operate on both LaneletMap and LaneletSubmap, consider using their common base class LaneletMapLayers as an input parameter for it.

Definition at line 451 of file LaneletMap.h.

Constructor & Destructor Documentation

◆ LaneletSubmap() [1/2]

lanelet::LaneletSubmap::LaneletSubmap ( )
default

◆ LaneletSubmap() [2/2]

lanelet::LaneletSubmap::LaneletSubmap ( LaneletMap &&  rhs)
inlineexplicitnoexcept

Constructs a submap from a moved-from LaneletMap.

Definition at line 457 of file LaneletMap.h.

Member Function Documentation

◆ add() [1/6]

void lanelet::LaneletSubmap::add ( Area  area)

adds an area

Definition at line 691 of file LaneletMap.cpp.

◆ add() [2/6]

void lanelet::LaneletSubmap::add ( const RegulatoryElementPtr regElem)

adds a new regulatory element to the submap.

Definition at line 697 of file LaneletMap.cpp.

◆ add() [3/6]

void lanelet::LaneletSubmap::add ( Lanelet  lanelet)

adds a lanelet to the submap

Exceptions
InvalidInputErrorif lanelet has a reglatory element without members

If the lanelet or elements owned by the lanelet have InvalId as Id, they will be assigned a new, unique id. Otherwise you are responsible for making sure that the id has not already been for a different element.

Definition at line 685 of file LaneletMap.cpp.

◆ add() [4/6]

void lanelet::LaneletSubmap::add ( LineString3d  lineString)

adds a new lineString the submap

Definition at line 708 of file LaneletMap.cpp.

◆ add() [5/6]

void lanelet::LaneletSubmap::add ( Point3d  point)

adds a new point to the submap

Definition at line 713 of file LaneletMap.cpp.

◆ add() [6/6]

void lanelet::LaneletSubmap::add ( Polygon3d  polygon)

adds a new polygon to the submap

Definition at line 703 of file LaneletMap.cpp.

◆ laneletMap() [1/2]

LaneletMapUPtr lanelet::LaneletSubmap::laneletMap ( )

◆ laneletMap() [2/2]

LaneletMapUPtr lanelet::LaneletSubmap::laneletMap ( ) const

Converts this into a fully valid lanelet map.

Definition at line 718 of file LaneletMap.cpp.

◆ LaneletMapLayers() [1/4]

lanelet::LaneletMapLayers::LaneletMapLayers
default

◆ LaneletMapLayers() [2/4]

lanelet::LaneletMapLayers::LaneletMapLayers

Construct from already initialized layers.

Parameters
laneletsnew lanelet layer
areasnew area layer
regulatoryElementsnew regulatoryElement layer
polygonspolygon layer
lineStringslinesting layer
pointspoint layer

Constructs a map from its individual elements for the layers. Unlike with the add functions you are responsible that e.g. all points of a linestring are in the point layer. However, this is the most efficient way to create a map because this will result in the most efficient RTree structure for fastest lookups.

Definition at line 557 of file LaneletMap.cpp.

◆ LaneletMapLayers() [3/4]

lanelet::LaneletMapLayers::LaneletMapLayers
delete

◆ LaneletMapLayers() [4/4]

lanelet::LaneletMapLayers::LaneletMapLayers
defaultnoexcept

◆ operator=()

LaneletSubmap& lanelet::LaneletSubmap::operator= ( LaneletMap &&  rhs)
inline

Definition at line 458 of file LaneletMap.h.

◆ trackParameters()

void lanelet::LaneletSubmap::trackParameters ( const RegulatoryElement regelem)

In order to let areas and lanelets get out of scope, this function ensures they stay alive. LaneletSubmap::add already handles this for you, so there is usually no need to call this.

Definition at line 747 of file LaneletMap.cpp.

Member Data Documentation

◆ regelemObjects_

std::vector<boost::variant<ConstLanelet, ConstArea> > lanelet::LaneletSubmap::regelemObjects_
private

In order to not let lanelets/areas referenced by regelems get out of scope, we keep a reference to them here.

Definition at line 499 of file LaneletMap.h.


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


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