Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
lanelet::PrimitiveLayer< T > Class Template Reference

Each primitive in lanelet2 has its own layer in the map. More...

#include <LaneletMap.h>

Classes

struct  Tree
 

Public Types

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< T >
 
using ConstPrimitiveVec = std::vector< ConstPrimitiveT >
 
using ConstSearchFunction = std::function< bool(const internal::SearchBoxT< T > &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, T >
 
using OptConstPrimitiveT = Optional< ConstPrimitiveT >
 
using OptPrimitiveT = Optional< PrimitiveT >
 
using PrimitiveT = T
 
using PrimitiveVec = std::vector< PrimitiveT >
 
using SearchFunction = std::function< bool(const internal::SearchBoxT< T > &box, const PrimitiveT &prim)>
 

Public Member Functions

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

Protected Member Functions

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

Map elements_
 the list of elements in this layer More...
 
std::unique_ptr< Treetree_
 Hides boost trees from you/the compiler. More...
 

Friends

class LaneletMap
 
class LaneletMapLayers
 
class LaneletSubmap
 

Detailed Description

template<typename T>
class lanelet::PrimitiveLayer< T >

Each primitive in lanelet2 has its own layer in the map.

This template class defines the common interface for these layers. It is only implemented for lanelet primitives and should not be instanciated with any other type.

Layers are an integral part of LaneletMap, they can not be created or modified without a LaneletMap object.

Internally, the elements are identified by their id, therefore it is absolutely important that an id is unique within one layer.

Definition at line 39 of file LaneletMap.h.

Member Typedef Documentation

◆ const_iterator

template<typename T >
using lanelet::PrimitiveLayer< T >::const_iterator = internal::TransformIterator<typename Map::const_iterator, const ConstPrimitiveT, internal::PairConverter<const ConstPrimitiveT> >

iterator that gives a const primitive, not a std::pair

Definition at line 56 of file LaneletMap.h.

◆ ConstPrimitiveT

template<typename T >
using lanelet::PrimitiveLayer< T >::ConstPrimitiveT = traits::ConstPrimitiveType<T>

Definition at line 42 of file LaneletMap.h.

◆ ConstPrimitiveVec

template<typename T >
using lanelet::PrimitiveLayer< T >::ConstPrimitiveVec = std::vector<ConstPrimitiveT>

Definition at line 44 of file LaneletMap.h.

◆ ConstSearchFunction

template<typename T >
using lanelet::PrimitiveLayer< T >::ConstSearchFunction = std::function<bool(const internal::SearchBoxT<T>& box, const ConstPrimitiveT& prim)>

Definition at line 155 of file LaneletMap.h.

◆ iterator

template<typename T >
using lanelet::PrimitiveLayer< T >::iterator = internal::TransformIterator<typename Map::iterator, PrimitiveT, internal::PairConverter<PrimitiveT> >

iterator that gives the primitive when dereferencing, not a std:pair

Definition at line 51 of file LaneletMap.h.

◆ Map

template<typename T >
using lanelet::PrimitiveLayer< T >::Map = std::unordered_map<Id, T>

Definition at line 43 of file LaneletMap.h.

◆ OptConstPrimitiveT

Definition at line 46 of file LaneletMap.h.

◆ OptPrimitiveT

template<typename T >
using lanelet::PrimitiveLayer< T >::OptPrimitiveT = Optional<PrimitiveT>

Definition at line 47 of file LaneletMap.h.

◆ PrimitiveT

template<typename T >
using lanelet::PrimitiveLayer< T >::PrimitiveT = T

Definition at line 41 of file LaneletMap.h.

◆ PrimitiveVec

template<typename T >
using lanelet::PrimitiveLayer< T >::PrimitiveVec = std::vector<PrimitiveT>

Definition at line 45 of file LaneletMap.h.

◆ SearchFunction

template<typename T >
using lanelet::PrimitiveLayer< T >::SearchFunction = std::function<bool(const internal::SearchBoxT<T>& box, const PrimitiveT& prim)>

Definition at line 156 of file LaneletMap.h.

Constructor & Destructor Documentation

◆ PrimitiveLayer() [1/5]

template<typename T >
lanelet::PrimitiveLayer< T >::PrimitiveLayer ( const PrimitiveLayer< T > &  rhs)
delete

◆ PrimitiveLayer() [2/5]

template<typename T >
lanelet::PrimitiveLayer< T >::PrimitiveLayer ( const Map primitives = Map())
explicitprotected

Definition at line 329 of file LaneletMap.cpp.

◆ PrimitiveLayer() [3/5]

template<typename T >
lanelet::PrimitiveLayer< T >::PrimitiveLayer ( PrimitiveLayer< T > &&  rhs)
protecteddefaultnoexcept

◆ ~PrimitiveLayer()

template<typename T >
lanelet::PrimitiveLayer< T >::~PrimitiveLayer ( )
protecteddefaultnoexcept

◆ PrimitiveLayer() [4/5]

Definition at line 337 of file LaneletMap.cpp.

◆ PrimitiveLayer() [5/5]

lanelet::PrimitiveLayer< Area >::PrimitiveLayer ( const PrimitiveLayer< T >::Map primitives)

Definition at line 345 of file LaneletMap.cpp.

Member Function Documentation

◆ add() [1/5]

void lanelet::PrimitiveLayer< Area >::add ( const Area area)
protected

Definition at line 392 of file LaneletMap.cpp.

◆ add() [2/5]

void lanelet::PrimitiveLayer< Lanelet >::add ( const Lanelet ll)
protected

Definition at line 399 of file LaneletMap.cpp.

◆ add() [3/5]

void lanelet::PrimitiveLayer< Point3d >::add ( const Point3d p)
protected

Definition at line 406 of file LaneletMap.cpp.

◆ add() [4/5]

Definition at line 413 of file LaneletMap.cpp.

◆ add() [5/5]

template<typename T >
void lanelet::PrimitiveLayer< T >::add ( const PrimitiveT element)
protected

Definition at line 383 of file LaneletMap.cpp.

◆ begin() [1/2]

template<typename T >
iterator lanelet::PrimitiveLayer< T >::begin ( )

iterator to beginning

Returns
the iterator

◆ begin() [2/2]

template<typename T >
PrimitiveLayer< T >::iterator lanelet::PrimitiveLayer< T >::begin

iterator to beginning of the elements (not ordered by id!)

Returns
the iterator

Definition at line 476 of file LaneletMap.cpp.

◆ empty()

template<typename T >
bool lanelet::PrimitiveLayer< T >::empty ( ) const
inline

returns whether this layer contains something

Returns
true if no elements

Definition at line 147 of file LaneletMap.h.

◆ end() [1/2]

template<typename T >
iterator lanelet::PrimitiveLayer< T >::end ( )

iterator to end

Returns
the iterator

◆ end() [2/2]

template<typename T >
PrimitiveLayer< T >::iterator lanelet::PrimitiveLayer< T >::end

iterator to end of the elements

Returns
the iterator

Definition at line 481 of file LaneletMap.cpp.

◆ exists()

template<typename T >
bool lanelet::PrimitiveLayer< T >::exists ( Id  id) const

checks whether an element exists in this layer

Parameters
idthe id identifying the element
Returns
true if element exists

Definition at line 354 of file LaneletMap.cpp.

◆ find() [1/2]

template<typename T >
PrimitiveLayer< T >::iterator lanelet::PrimitiveLayer< T >::find ( Id  id)

non-const version of finding an element

Parameters
idthe id to look for
Returns
iterator to the matching element or end()

Definition at line 486 of file LaneletMap.cpp.

◆ find() [2/2]

template<typename T >
PrimitiveLayer< T >::const_iterator lanelet::PrimitiveLayer< T >::find ( Id  id) const

find returns an iterator to an element if it exists

Parameters
idid to look for
Returns
iterator to the element or end()

Note that dereferencing the iterator will give you only the primitive, not a std::pair as usual with normal std::maps!

Definition at line 471 of file LaneletMap.cpp.

◆ findUsages() [1/2]

template<typename T >
std::vector< typename PrimitiveLayer< T >::PrimitiveT > lanelet::PrimitiveLayer< T >::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.

Definition at line 427 of file LaneletMap.cpp.

◆ findUsages() [2/2]

template<typename T >
std::vector<ConstPrimitiveT> lanelet::PrimitiveLayer< T >::findUsages ( const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &  primitive) const

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.

◆ get() [1/2]

template<typename T >
PrimitiveLayer< T >::PrimitiveT lanelet::PrimitiveLayer< T >::get ( Id  id)

returns an element for this id if it exists

Parameters
idthe id identifying the element
Exceptions
NoSuchPrimitiveErrorif the element does not exist
Returns
the non-const version of the element

Definition at line 359 of file LaneletMap.cpp.

◆ get() [2/2]

template<typename T >
PrimitiveLayer< T >::ConstPrimitiveT lanelet::PrimitiveLayer< T >::get ( Id  id) const

returns an element for this id if it exists

Parameters
idthe id identifying the element
Exceptions
NoSuchPrimitiveErrorif the element does not exist
Returns
the const version of the element

Definition at line 371 of file LaneletMap.cpp.

◆ nearest() [1/4]

template<typename T >
PrimitiveLayer< T >::PrimitiveVec lanelet::PrimitiveLayer< T >::nearest ( const BasicPoint2d point,
unsigned  n 
)

Definition at line 533 of file LaneletMap.cpp.

◆ nearest() [2/4]

template<typename T >
PrimitiveLayer< T >::ConstPrimitiveVec lanelet::PrimitiveLayer< T >::nearest ( const BasicPoint2d point,
unsigned  n 
) const

search for the n nearest elements to a point

Parameters
pointthe point for the query
nnumber of elements returned
Returns
the element whose bounding boxes are closest to the point
See also
nearestUntil, lanelet::geometry::findNearest

Note that this function does not yield accurate results for all primitives except points. For all other primitives, "nearest" is determined by the bounding box of the object. For regulatory elements, this will be the bounding box of all parameters of the regulatory element. For Lanelets, it will be the bounding box alround the polygon.

If you are not happy with this, have a look at nearestUntil, or one of the free functions, like geometry::findNearest.

Definition at line 526 of file LaneletMap.cpp.

◆ nearest() [3/4]

template<typename T >
PrimitiveVec lanelet::PrimitiveLayer< T >::nearest ( const Point2d point,
unsigned  n 
)
inline

Definition at line 206 of file LaneletMap.h.

◆ nearest() [4/4]

template<typename T >
ConstPrimitiveVec lanelet::PrimitiveLayer< T >::nearest ( const Point2d point,
unsigned  n 
) const
inline

Definition at line 205 of file LaneletMap.h.

◆ nearestUntil() [1/4]

template<typename T >
PrimitiveLayer< T >::OptConstPrimitiveT lanelet::PrimitiveLayer< T >::nearestUntil ( const BasicPoint2d point,
const ConstSearchFunction func 
) const

repeatedly calls a user-defined predicate until it returns true.

Returns
the element for which the function returned true. If it was never true, an empty Optional is returned.

Starting at the primitive with the closest bounding-box distance to the query point iteratively calls func until true is returned. This can be used for iterative queries.

Definition at line 541 of file LaneletMap.cpp.

◆ nearestUntil() [2/4]

template<typename T >
PrimitiveLayer< T >::OptPrimitiveT lanelet::PrimitiveLayer< T >::nearestUntil ( const BasicPoint2d point,
const SearchFunction func 
)

Definition at line 547 of file LaneletMap.cpp.

◆ nearestUntil() [3/4]

template<typename T >
OptConstPrimitiveT lanelet::PrimitiveLayer< T >::nearestUntil ( const ConstPoint2d point,
const ConstSearchFunction func 
) const
inline

Definition at line 219 of file LaneletMap.h.

◆ nearestUntil() [4/4]

template<typename T >
OptPrimitiveT lanelet::PrimitiveLayer< T >::nearestUntil ( const Point2d point,
const SearchFunction func 
)
inline

Definition at line 222 of file LaneletMap.h.

◆ operator=() [1/2]

template<typename T >
PrimitiveLayer& lanelet::PrimitiveLayer< T >::operator= ( const PrimitiveLayer< T > &  rhs)
delete

◆ operator=() [2/2]

template<typename T >
PrimitiveLayer< T > & lanelet::PrimitiveLayer< T >::operator= ( PrimitiveLayer< T > &&  rhs)
protecteddefaultnoexcept

◆ remove()

template<typename T >
void lanelet::PrimitiveLayer< T >::remove ( Id  element)
protected

◆ search() [1/2]

template<typename T >
PrimitiveLayer< T >::PrimitiveVec lanelet::PrimitiveLayer< T >::search ( const BoundingBox2d area)

Definition at line 507 of file LaneletMap.cpp.

◆ search() [2/2]

template<typename T >
PrimitiveLayer< T >::ConstPrimitiveVec lanelet::PrimitiveLayer< T >::search ( const BoundingBox2d area) const

searches for elements within a search area

Parameters
areathe search area in the map
Returns
a immutable list of matching elements

The search is done by comparing bounding boxes, therefore this function might return false positives because the elements do not intersect with the area, but their bounding boxes do. To sort these out use lanelet::geometry::intersects or lanelet::geometry::overlaps.

Note that this function is also implemented for the point layer for consistency, even if it does not make sense for this type. It will always return an empty vector.

Definition at line 500 of file LaneletMap.cpp.

◆ searchUntil() [1/2]

template<typename T >
PrimitiveLayer< T >::OptConstPrimitiveT lanelet::PrimitiveLayer< T >::searchUntil ( const BoundingBox2d area,
const ConstSearchFunction func 
) const

searches within search area until a search function returns true.

Returns
the element for which the function returned true
See also
nearestUntil

Starting by the object with the closest bounding box, searchUntil will pass primitives to func until the result is true. This is the returned object. If no such object exists, the Optional will be empty.

Definition at line 514 of file LaneletMap.cpp.

◆ searchUntil() [2/2]

template<typename T >
PrimitiveLayer< T >::OptPrimitiveT lanelet::PrimitiveLayer< T >::searchUntil ( const BoundingBox2d area,
const SearchFunction func 
)

Definition at line 520 of file LaneletMap.cpp.

◆ size()

template<typename T >
size_t lanelet::PrimitiveLayer< T >::size ( ) const
inline

returns number of elements in this layer

Returns
number of elements

Definition at line 153 of file LaneletMap.h.

◆ uniqueId()

template<typename T >
Id lanelet::PrimitiveLayer< T >::uniqueId

returns a unique id. it is guaranteed that the id is not used within this layer

Returns
an unused id

Several calls to uniqueId might or might not produce the same Id, as long as no element with this Id was added to the layer

Definition at line 553 of file LaneletMap.cpp.

Friends And Related Function Documentation

◆ LaneletMap

template<typename T >
friend class LaneletMap
friend

Definition at line 237 of file LaneletMap.h.

◆ LaneletMapLayers

template<typename T >
friend class LaneletMapLayers
friend

Definition at line 238 of file LaneletMap.h.

◆ LaneletSubmap

template<typename T >
friend class LaneletSubmap
friend

Definition at line 239 of file LaneletMap.h.

Member Data Documentation

◆ elements_

template<typename T >
Map lanelet::PrimitiveLayer< T >::elements_
protected

the list of elements in this layer

Definition at line 249 of file LaneletMap.h.

◆ tree_

template<typename T >
std::unique_ptr<Tree> lanelet::PrimitiveLayer< T >::tree_
protected

Hides boost trees from you/the compiler.

Definition at line 250 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:53