Class LaneletMapLayers

Inheritance Relationships

Derived Types

Class Documentation

class LaneletMapLayers

Container for all layers of a lanelet map. Used by both LaneletMap and LaneletSubmap.

Subclassed by lanelet::LaneletMap, lanelet::LaneletSubmap

Public Functions

LaneletMapLayers() = default
LaneletMapLayers(LaneletMapLayers &&rhs) noexcept = default
LaneletMapLayers &operator=(LaneletMapLayers &&rhs) noexcept = default
LaneletMapLayers(const LaneletMapLayers &rhs) = delete
LaneletMapLayers &operator=(const LaneletMapLayers &rhs) = delete
~LaneletMapLayers() noexcept = 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.

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

inline bool empty() const noexcept

Returns whether all layers of this object are empty.

inline size_t size() const noexcept

Returns the total number of elements in all layers.

Public Members

LaneletLayer laneletLayer

access to the lanelets within this map

AreaLayer areaLayer

access to areas

RegulatoryElementLayer regulatoryElementLayer

access to regElems

PolygonLayer polygonLayer

access to the polygons

LineStringLayer lineStringLayer

access to the lineStrings

PointLayer pointLayer

access to the points