Class LaneletSubmap
Defined in File LaneletMap.h
Inheritance Relationships
Base Type
public lanelet::LaneletMapLayers
(Class LaneletMapLayers)
Class Documentation
-
class LaneletSubmap : public lanelet::LaneletMapLayers
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.
Public Functions
-
LaneletSubmap() = default
-
inline explicit LaneletSubmap(LaneletMap &&rhs) noexcept
Constructs a submap from a moved-from LaneletMap.
-
inline LaneletSubmap &operator=(LaneletMap &&rhs)
-
void add(Lanelet lanelet)
adds a lanelet to the submap
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.
- Throws:
InvalidInputError – if lanelet has a reglatory element without members
-
void add(const RegulatoryElementPtr ®Elem)
adds a new regulatory element to the submap.
-
void add(LineString3d lineString)
adds a new lineString the submap
-
LaneletMapConstPtr laneletMap() const
Converts this into a fully valid lanelet map.
-
LaneletMapUPtr laneletMap()
-
void trackParameters(const RegulatoryElement ®elem)
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.
-
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.
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.
- Parameters:
lanelets – new lanelet layer
areas – new area layer
regulatoryElements – new regulatoryElement layer
polygons – polygon layer
lineStrings – linesting layer
points – point layer
-
LaneletSubmap() = default