Classes | Namespaces | Macros | Typedefs | Functions
LaneletMap.h File Reference
#include <unordered_map>
#include "lanelet2_core/Forward.h"
#include "lanelet2_core/primitives/Area.h"
#include "lanelet2_core/primitives/BoundingBox.h"
#include "lanelet2_core/primitives/Lanelet.h"
#include "lanelet2_core/primitives/RegulatoryElement.h"
#include "lanelet2_core/utility/Utilities.h"
Include dependency graph for LaneletMap.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  lanelet::AreaLayer
 Specialized map layer for Area. More...
 
class  lanelet::LaneletLayer
 Specialized map layer for Lanelet. More...
 
class  lanelet::LaneletMap
 Basic element for accessing and managing the elements of a map. More...
 
class  lanelet::LaneletMapLayers
 Container for all layers of a lanelet map. Used by both LaneletMap and LaneletSubmap. More...
 
class  lanelet::LaneletSubmap
 A LaneletSubmap only contains the elemets that have be expleicitly added to it. More...
 
struct  lanelet::traits::LayerPrimitive< T >
 
struct  lanelet::traits::LayerPrimitive< const T >
 
class  lanelet::PrimitiveLayer< T >
 Each primitive in lanelet2 has its own layer in the map. More...
 
struct  lanelet::internal::SearchBox< T >
 
struct  lanelet::internal::SearchBox< Point3d >
 

Namespaces

 lanelet
 
 lanelet::geometry
 
 lanelet::internal
 
 lanelet::traits
 
 lanelet::utils
 

Macros

#define EXTERN_CONST_FIND_NEAREST(PRIM)   extern template std::vector<std::pair<double, traits::ConstPrimitiveType<PRIM>>> findNearest(const PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
 
#define EXTERN_FIND_NEAREST(PRIM)   extern template std::vector<std::pair<double, PRIM>> findNearest(PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
 

Typedefs

template<typename PrimitiveT >
using lanelet::utils::ConstLayerPrimitive = typename PrimitiveLayer< PrimitiveT >::ConstPrimitiveT
 
template<typename T >
using lanelet::traits::LayerPrimitiveType = typename LayerPrimitive< T >::Type
 
using lanelet::LineStringLayer = PrimitiveLayer< LineString3d >
 
using lanelet::PointLayer = PrimitiveLayer< Point3d >
 
using lanelet::PolygonLayer = PrimitiveLayer< Polygon3d >
 
using lanelet::RegulatoryElementLayer = PrimitiveLayer< RegulatoryElementPtr >
 
template<typename T >
using lanelet::internal::SearchBoxT = typename SearchBox< T >::Type
 

Functions

LaneletMapConstUPtr lanelet::utils::createConstMap (const ConstLanelets &fromLanelets, const ConstAreas &fromAreas)
 
LaneletSubmapConstUPtr lanelet::utils::createConstSubmap (const ConstLanelets &fromLanelets, const ConstAreas &fromAreas)
 
LaneletMapUPtr lanelet::utils::createMap (const Areas &fromAreas)
 
LaneletMapUPtr lanelet::utils::createMap (const Lanelets &fromLanelets)
 
LaneletMapUPtr lanelet::utils::createMap (const Lanelets &fromLanelets, const Areas &fromAreas)
 
LaneletMapUPtr lanelet::utils::createMap (const LineStrings3d &fromLineStrings)
 
LaneletMapUPtr lanelet::utils::createMap (const Points3d &fromPoints)
 Efficiently create a LaneletMap from a vector of things. All elements must have a valid id! More...
 
LaneletMapUPtr lanelet::utils::createMap (const Polygons3d &fromPolygons)
 
LaneletSubmapUPtr lanelet::utils::createSubmap (const Areas &fromAreas)
 
LaneletSubmapUPtr lanelet::utils::createSubmap (const Lanelets &fromLanelets)
 
LaneletSubmapUPtr lanelet::utils::createSubmap (const Lanelets &fromLanelets, const Areas &fromAreas)
 
LaneletSubmapUPtr lanelet::utils::createSubmap (const LineStrings3d &fromLineStrings)
 
LaneletSubmapUPtr lanelet::utils::createSubmap (const Points3d &fromPoints)
 Efficiently create a LaneletSubmap from a vector of things. All elements must have a valid id! More...
 
LaneletSubmapUPtr lanelet::utils::createSubmap (const Polygons3d &fromPolygons)
 
 lanelet::geometry::EXTERN_CONST_FIND_NEAREST (Area)
 
 lanelet::geometry::EXTERN_CONST_FIND_NEAREST (Lanelet)
 
 lanelet::geometry::EXTERN_CONST_FIND_NEAREST (LineString3d)
 
 lanelet::geometry::EXTERN_CONST_FIND_NEAREST (Point3d)
 
 lanelet::geometry::EXTERN_CONST_FIND_NEAREST (Polygon3d)
 
 lanelet::geometry::EXTERN_CONST_FIND_NEAREST (RegulatoryElementPtr)
 
 lanelet::geometry::EXTERN_FIND_NEAREST (Area)
 
 lanelet::geometry::EXTERN_FIND_NEAREST (Lanelet)
 
 lanelet::geometry::EXTERN_FIND_NEAREST (LineString3d)
 
 lanelet::geometry::EXTERN_FIND_NEAREST (Point3d)
 
 lanelet::geometry::EXTERN_FIND_NEAREST (Polygon3d)
 
 lanelet::geometry::EXTERN_FIND_NEAREST (RegulatoryElementPtr)
 
template<typename PrimT >
std::vector< std::pair< double, traits::ConstPrimitiveType< PrimT > > > lanelet::geometry::findNearest (const PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count)
 
template<typename PrimT >
std::vector< std::pair< double, PrimT > > lanelet::geometry::findNearest (PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count)
 returns the nearest n primitives to a point. More...
 
template<typename PrimitiveT >
std::vector< ConstLayerPrimitive< PrimitiveT > > lanelet::utils::findUsages (const PrimitiveLayer< PrimitiveT > &layer, Id id)
 
ConstAreas lanelet::utils::findUsagesInAreas (const LaneletMapLayers &map, const ConstPoint3d &p)
 
ConstLanelets lanelet::utils::findUsagesInLanelets (const LaneletMapLayers &map, const ConstPoint3d &p)
 
Id lanelet::utils::getId ()
 returns a unique id by incrementing a counter each time this is called. More...
 
void lanelet::utils::registerId (Id id)
 

Macro Definition Documentation

◆ EXTERN_CONST_FIND_NEAREST

#define EXTERN_CONST_FIND_NEAREST (   PRIM)    extern template std::vector<std::pair<double, traits::ConstPrimitiveType<PRIM>>> findNearest(const PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)

Definition at line 589 of file LaneletMap.h.

◆ EXTERN_FIND_NEAREST

#define EXTERN_FIND_NEAREST (   PRIM)    extern template std::vector<std::pair<double, PRIM>> findNearest(PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)

Definition at line 587 of file LaneletMap.h.



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