Public Member Functions | Private Member Functions | Friends | List of all members
lanelet::LaneletLayer Class Reference

Specialized map layer for Lanelet. More...

#include <LaneletMap.h>

Inheritance diagram for lanelet::LaneletLayer:
Inheritance graph
[legend]

Public Member Functions

Lanelets findUsages (const RegulatoryElementConstPtr &regElem)
 
ConstLanelets findUsages (const RegulatoryElementConstPtr &regElem) const
 
std::vector< PrimitiveTfindUsages (const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &primitive)
 finds usages of an owned type within this layer More...
 
std::vector< ConstPrimitiveTfindUsages (const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &primitive) const
 finds usages of an owned type within this layer More...
 
 LaneletLayer ()=default
 
 LaneletLayer (const LaneletLayer &)=delete
 
LaneletLayer operator= (LaneletLayer &)=delete
 
 ~LaneletLayer ()=default
 
- Public Member Functions inherited from lanelet::PrimitiveLayer< Lanelet >
iterator begin ()
 iterator to beginning More...
 
const_iterator begin () const
 iterator to beginning of the elements (not ordered by id!) More...
 
bool empty () const
 returns whether this layer contains something More...
 
iterator end ()
 iterator to end More...
 
const_iterator end () const
 iterator to end of the elements More...
 
bool exists (Id id) const
 checks whether an element exists in this layer More...
 
iterator find (Id id)
 non-const version of finding an element More...
 
const_iterator find (Id id) const
 find returns an iterator to an element if it exists More...
 
std::vector< PrimitiveTfindUsages (const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &primitive)
 finds usages of an owned type within this layer More...
 
std::vector< ConstPrimitiveTfindUsages (const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &primitive) const
 finds usages of an owned type within this layer More...
 
PrimitiveT get (Id id)
 returns an element for this id if it exists More...
 
ConstPrimitiveT get (Id id) const
 returns an element for this id if it exists More...
 
PrimitiveVec nearest (const BasicPoint2d &point, unsigned n)
 
ConstPrimitiveVec nearest (const BasicPoint2d &point, unsigned n) const
 search for the n nearest elements to a point More...
 
PrimitiveVec nearest (const Point2d &point, unsigned n)
 
ConstPrimitiveVec nearest (const Point2d &point, unsigned n) const
 
OptConstPrimitiveT nearestUntil (const BasicPoint2d &point, const ConstSearchFunction &func) const
 repeatedly calls a user-defined predicate until it returns true. More...
 
OptPrimitiveT nearestUntil (const BasicPoint2d &point, const SearchFunction &func)
 
OptConstPrimitiveT nearestUntil (const ConstPoint2d &point, const ConstSearchFunction &func) const
 
OptPrimitiveT nearestUntil (const Point2d &point, const SearchFunction &func)
 
PrimitiveLayeroperator= (const PrimitiveLayer &rhs)=delete
 
 PrimitiveLayer (const PrimitiveLayer &rhs)=delete
 
 PrimitiveLayer (const PrimitiveLayer::Map &primitives)
 
 PrimitiveLayer (const PrimitiveLayer::Map &primitives)
 
PrimitiveVec search (const BoundingBox2d &area)
 
ConstPrimitiveVec search (const BoundingBox2d &area) const
 searches for elements within a search area More...
 
OptConstPrimitiveT searchUntil (const BoundingBox2d &area, const ConstSearchFunction &func) const
 searches within search area until a search function returns true. More...
 
OptPrimitiveT searchUntil (const BoundingBox2d &area, const SearchFunction &func)
 
size_t size () const
 returns number of elements in this layer More...
 
Id uniqueId () const
 returns a unique id. it is guaranteed that the id is not used within this layer More...
 

Private Member Functions

 LaneletLayer (LaneletLayer &&rhs) noexcept=default
 
LaneletLayeroperator= (LaneletLayer &&rhs) noexcept=default
 

Friends

class LaneletMap
 
class LaneletMapLayers
 
class LaneletSubmap
 

Additional Inherited Members

- Public Types inherited from lanelet::PrimitiveLayer< Lanelet >
using const_iterator = internal::TransformIterator< typename Map::const_iterator, const ConstPrimitiveT, internal::PairConverter< const ConstPrimitiveT > >
 iterator that gives a const primitive, not a std::pair More...
 
using ConstPrimitiveT = traits::ConstPrimitiveType< Lanelet >
 
using ConstPrimitiveVec = std::vector< ConstPrimitiveT >
 
using ConstSearchFunction = std::function< bool(const internal::SearchBoxT< Lanelet > &box, const ConstPrimitiveT &prim)>
 
using iterator = internal::TransformIterator< typename Map::iterator, PrimitiveT, internal::PairConverter< PrimitiveT > >
 iterator that gives the primitive when dereferencing, not a std:pair More...
 
using Map = std::unordered_map< Id, Lanelet >
 
using OptConstPrimitiveT = Optional< ConstPrimitiveT >
 
using OptPrimitiveT = Optional< PrimitiveT >
 
using PrimitiveT = Lanelet
 
using PrimitiveVec = std::vector< PrimitiveT >
 
using SearchFunction = std::function< bool(const internal::SearchBoxT< Lanelet > &box, const PrimitiveT &prim)>
 
- Protected Member Functions inherited from lanelet::PrimitiveLayer< Lanelet >
void add (const Area &area)
 
void add (const Lanelet &ll)
 
void add (const Point3d &p)
 
void add (const PrimitiveLayer< RegulatoryElementPtr >::PrimitiveT &element)
 
void add (const PrimitiveT &element)
 
PrimitiveLayeroperator= (PrimitiveLayer &&rhs) noexcept
 
 PrimitiveLayer (const Map &primitives=Map())
 
 PrimitiveLayer (PrimitiveLayer &&rhs) noexcept
 
void remove (Id element)
 
 ~PrimitiveLayer () noexcept
 
- Protected Attributes inherited from lanelet::PrimitiveLayer< Lanelet >
Map elements_
 the list of elements in this layer More...
 
std::unique_ptr< Tree > tree_
 Hides boost trees from you/the compiler. More...
 

Detailed Description

Specialized map layer for Lanelet.

Definition at line 286 of file LaneletMap.h.

Constructor & Destructor Documentation

◆ LaneletLayer() [1/3]

lanelet::LaneletLayer::LaneletLayer ( )
default

◆ ~LaneletLayer()

lanelet::LaneletLayer::~LaneletLayer ( )
default

◆ LaneletLayer() [2/3]

lanelet::LaneletLayer::LaneletLayer ( const LaneletLayer )
delete

◆ LaneletLayer() [3/3]

lanelet::LaneletLayer::LaneletLayer ( LaneletLayer &&  rhs)
privatedefaultnoexcept

Member Function Documentation

◆ findUsages() [1/4]

Lanelets lanelet::LaneletLayer::findUsages ( const RegulatoryElementConstPtr regElem)

Definition at line 453 of file LaneletMap.cpp.

◆ findUsages() [2/4]

ConstLanelets lanelet::LaneletLayer::findUsages ( const RegulatoryElementConstPtr regElem) const

Definition at line 458 of file LaneletMap.cpp.

◆ findUsages() [3/4]

std::vector< typename PrimitiveLayer< T >::PrimitiveT > lanelet::PrimitiveLayer< T >::findUsages

finds usages of an owned type within this layer

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

Definition at line 427 of file LaneletMap.cpp.

◆ findUsages() [4/4]

std::vector<ConstPrimitiveT> lanelet::PrimitiveLayer< T >::findUsages

finds usages of an owned type within this layer

See also
utils::findUsages

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

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

◆ operator=() [1/2]

LaneletLayer& lanelet::LaneletLayer::operator= ( LaneletLayer &&  rhs)
privatedefaultnoexcept

◆ operator=() [2/2]

LaneletLayer lanelet::LaneletLayer::operator= ( LaneletLayer )
delete

Friends And Related Function Documentation

◆ LaneletMap

friend class LaneletMap
friend

Definition at line 297 of file LaneletMap.h.

◆ LaneletMapLayers

friend class LaneletMapLayers
friend

Definition at line 298 of file LaneletMap.h.

◆ LaneletSubmap

friend class LaneletSubmap
friend

Definition at line 299 of file LaneletMap.h.


The documentation for this class was generated from the following files:


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52