Template Function lanelet::geometry::findWithin3d
Defined in File LaneletMap.h
Function Documentation
-
template<typename LayerT, typename GeometryT>
auto lanelet::geometry::findWithin3d(LayerT &layer, const GeometryT &geometry, double maxDist = 0.) -> std::vector<std::pair<double, traits::LayerPrimitiveType<LayerT>>> Returns all elements that are closer than maxDist to a geometry in 3d.
- Parameters:
layer – for the check (a layer of LaneletMap)
geometry – to check (any 3d geometry)
maxDist – maximum distance to the input geometry. If zero, only primitives containing the element are returned. Be aware that rounding errors can affect the result for primitives directly on (or very close to) the boundary.
- Returns:
vector of pairs: <actual distance, element> of all elements of a layer which are closer than maxDist to the geometry. The return type differs depending on if the layer is const or not. Result sorted in ascending distance.