Class LaneletMap

Inheritance Relationships

Base Type

Class Documentation

class LaneletMap : public lanelet::LaneletMapLayers

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.

Public Functions

void add(Lanelet lanelet)

adds a lanelet and all the elements it owns to the map

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(Area area)

adds an area and all the elements it owns

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.

Parameters:

area – the area to add

Throws:

InvalidInputError – if area has a reglatory element without members

void add(const RegulatoryElementPtr &regElem)

adds a new regulatory element and all elements it owns to the map.

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.

Throws:
void 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.

void 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.

void 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.

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