Template Class PrimitiveLayer
Defined in File LaneletMap.h
Class Documentation
-
template<typename T>
class PrimitiveLayer 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.
Public Types
-
using ConstPrimitiveT = traits::ConstPrimitiveType<T>
-
using ConstPrimitiveVec = std::vector<ConstPrimitiveT>
-
using PrimitiveVec = std::vector<PrimitiveT>
-
using OptConstPrimitiveT = Optional<ConstPrimitiveT>
-
using OptPrimitiveT = Optional<PrimitiveT>
-
using iterator = internal::TransformIterator<typename Map::iterator, PrimitiveT, internal::PairConverter<PrimitiveT>>
iterator that gives the primitive when dereferencing, not a std:pair
-
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
-
using ConstSearchFunction = std::function<bool(const internal::SearchBoxT<T> &box, const ConstPrimitiveT &prim)>
-
using SearchFunction = std::function<bool(const internal::SearchBoxT<T> &box, const PrimitiveT &prim)>
Public Functions
-
PrimitiveLayer(const PrimitiveLayer &rhs) = delete
-
PrimitiveLayer &operator=(const PrimitiveLayer &rhs) = delete
-
bool exists(Id id) const
checks whether an element exists in this layer
- Parameters:
id – the id identifying the element
- Returns:
true if element exists
-
ConstPrimitiveT get(Id id) const
returns an element for this id if it exists
- Parameters:
id – the id identifying the element
- Throws:
NoSuchPrimitiveError – if the element does not exist
- Returns:
the const version of the element
-
PrimitiveT get(Id id)
returns an element for this id if it exists
- Parameters:
id – the id identifying the element
- Throws:
NoSuchPrimitiveError – if the element does not exist
- Returns:
the non-const version of the element
-
const_iterator find(Id id) const
find returns an iterator to an element if it exists
Note that dereferencing the iterator will give you only the primitive, not a std::pair as usual with normal std::maps!
- Parameters:
id – id to look for
- Returns:
iterator to the element or end()
-
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.
-
const_iterator begin() const
iterator to beginning of the elements (not ordered by id!)
- Returns:
the iterator
-
const_iterator end() const
iterator to end of the elements
- Returns:
the iterator
-
iterator find(Id id)
non-const version of finding an element
- Parameters:
id – the id to look for
- Returns:
iterator to the matching element or end()
-
inline bool empty() const
returns whether this layer contains something
- Returns:
true if no elements
-
inline size_t size() const
returns number of elements in this layer
- Returns:
number of elements
-
ConstPrimitiveVec search(const BoundingBox2d &area) const
searches for elements within a search area
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.
- Parameters:
area – the search area in the map
- Returns:
a immutable list of matching elements
-
PrimitiveVec search(const BoundingBox2d &area)
-
OptConstPrimitiveT searchUntil(const BoundingBox2d &area, const ConstSearchFunction &func) const
searches within search area until a search function returns true.
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.
See also
- Returns:
the element for which the function returned true
-
OptPrimitiveT searchUntil(const BoundingBox2d &area, const SearchFunction &func)
-
ConstPrimitiveVec nearest(const BasicPoint2d &point, unsigned n) const
search for the n nearest elements to a point
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.
See also
nearestUntil, lanelet::geometry::findNearest
If you are not happy with this, have a look at nearestUntil, or one of the free functions, like geometry::findNearest.
- Parameters:
point – the point for the query
n – number of elements returned
- Returns:
the element whose bounding boxes are closest to the point
-
PrimitiveVec nearest(const BasicPoint2d &point, unsigned n)
-
inline ConstPrimitiveVec nearest(const Point2d &point, unsigned n) const
-
inline PrimitiveVec nearest(const Point2d &point, unsigned n)
-
OptConstPrimitiveT nearestUntil(const BasicPoint2d &point, const ConstSearchFunction &func) const
repeatedly calls a user-defined predicate until it returns true.
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.
- Returns:
the element for which the function returned true. If it was never true, an empty Optional is returned.
-
OptPrimitiveT nearestUntil(const BasicPoint2d &point, const SearchFunction &func)
-
inline OptConstPrimitiveT nearestUntil(const ConstPoint2d &point, const ConstSearchFunction &func) const
-
inline OptPrimitiveT nearestUntil(const Point2d &point, const SearchFunction &func)
Protected Functions
-
PrimitiveLayer(PrimitiveLayer &&rhs) noexcept
-
PrimitiveLayer &operator=(PrimitiveLayer &&rhs) noexcept
-
~PrimitiveLayer() noexcept
-
void add(const PrimitiveT &element)
Protected Attributes
-
std::unique_ptr<Tree> tree_
Hides boost trees from you/the compiler.
Friends
- friend class LaneletMap
- friend class LaneletMapLayers
- friend class LaneletSubmap
-
using ConstPrimitiveT = traits::ConstPrimitiveType<T>