Class LaneletLayer

Inheritance Relationships

Base Type

Class Documentation

class LaneletLayer : public lanelet::PrimitiveLayer<Lanelet>

Specialized map layer for Lanelet.

Public Functions

LaneletLayer() = default
~LaneletLayer() = default
LaneletLayer(const LaneletLayer&) = delete
LaneletLayer operator=(LaneletLayer&) = delete
Lanelets findUsages(const RegulatoryElementConstPtr &regElem)
ConstLanelets findUsages(const RegulatoryElementConstPtr &regElem) const
std::vector<ConstPrimitiveT> findUsages(const traits::ConstPrimitiveType<traits::OwnedT<PrimitiveT>> &primitive) const

finds usages of an owned type within this layer

Finds e.g. points owned by linestrings in the lanelet layer.

See also

utils::findUsages

The relations are stored by a map internally, so this is just a fast map lookup.

std::vector<PrimitiveT> findUsages(const traits::ConstPrimitiveType<traits::OwnedT<PrimitiveT>> &primitive)

finds usages of an owned type within this layer

This is the non-const version to find usages of a primitive in a layer.