Basic element for accessing and managing the elements of a map. More...
#include <LaneletMap.h>

Public Member Functions | |
| void | add (Lanelet lanelet) |
| adds a lanelet and all the elements it owns to the map More... | |
| void | add (Area area) |
| adds an area and all the elements it owns More... | |
| void | add (const RegulatoryElementPtr ®Elem) |
| adds a new regulatory element and all elements it owns to the map. More... | |
| void | add (Polygon3d polygon) |
| adds a new polygon and all elements it owns to the map. More... | |
| void | add (LineString3d lineString) |
| adds a new lineString and all elements it owns to the map. More... | |
| void | add (Point3d point) |
| adds a new point and all elements it owns to the map. More... | |
Public Member Functions inherited from lanelet::LaneletMapLayers | |
| bool | empty () const noexcept |
| Returns whether all layers of this object are empty. More... | |
| LaneletMapLayers ()=default | |
| LaneletMapLayers (LaneletMapLayers &&rhs) noexcept=default | |
| LaneletMapLayers (const LaneletMapLayers &rhs)=delete | |
| LaneletMapLayers (const LaneletLayer::Map &lanelets, const AreaLayer::Map &areas, const RegulatoryElementLayer::Map ®ulatoryElements, const PolygonLayer::Map &polygons, const LineStringLayer::Map &lineStrings, const PointLayer::Map &points) | |
| Construct from already initialized layers. More... | |
| LaneletMapLayers & | operator= (LaneletMapLayers &&rhs) noexcept=default |
| LaneletMapLayers & | operator= (const LaneletMapLayers &rhs)=delete |
| size_t | size () const noexcept |
| Returns the total number of elements in all layers. More... | |
| ~LaneletMapLayers () noexcept=default | |
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... | |
Basic element for accessing and managing the elements of a map.
The map is divided in individual layers, one for each primitive in lanelet2. Each layer offers efficient functions to find elements by its id or spacial position. A LaneletMap can not be copied because maps are unique. You can only std::move them.
A LaneletMap is designed to be always self contained. This means it always contains all elements that are used by any element in the map. If you add a Lanelet, all its LineString boundaries, all RegulatoryElements, all things referenced by the regulatory elements are added to the map as well. This also means that if a lanelet has regulatory elements that in turn also reference lanelets, these lanelets will also be added to the map. If this behaviour is not what you want, consider using a LaneletSubmap.
Definition at line 375 of file LaneletMap.h.
| void lanelet::LaneletMap::add | ( | Lanelet | lanelet | ) |
adds a lanelet and all the elements it owns to the map
| InvalidInputError | if 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 568 of file LaneletMap.cpp.
| void lanelet::LaneletMap::add | ( | Area | area | ) |
adds an area and all the elements it owns
| area | the area to add |
| InvalidInputError | if area has a reglatory element without members |
If the area or elements owned by it 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 594 of file LaneletMap.cpp.
| void lanelet::LaneletMap::add | ( | const RegulatoryElementPtr & | regElem | ) |
adds a new regulatory element and all elements it owns to the map.
| NullptrError | if regElem is a nullptr |
| InvalidInputError | if regElem has no members |
If the regulatory elemnet or elements owned it 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 623 of file LaneletMap.cpp.
| void lanelet::LaneletMap::add | ( | Polygon3d | polygon | ) |
adds a new polygon and all elements it owns to the map.
If the polygon or elements owned by it 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 646 of file LaneletMap.cpp.
| void lanelet::LaneletMap::add | ( | LineString3d | lineString | ) |
adds a new lineString and all elements it owns to the map.
If the lineString or elements owned by it 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 660 of file LaneletMap.cpp.
| void lanelet::LaneletMap::add | ( | Point3d | point | ) |
adds a new point and all elements it owns to the map.
If the point or elements owned by it 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 674 of file LaneletMap.cpp.