Classes | Namespaces | Macros | Functions
LaneletMap.cpp File Reference
#include "lanelet2_core/LaneletMap.h"
#include <atomic>
#include <boost/geometry/algorithms/disjoint.hpp>
#include <boost/geometry/algorithms/equals.hpp>
#include <boost/geometry/index/rtree.hpp>
#include <chrono>
#include <random>
#include "lanelet2_core/geometry/Area.h"
#include "lanelet2_core/geometry/BoundingBox.h"
#include "lanelet2_core/geometry/Lanelet.h"
#include "lanelet2_core/geometry/LineString.h"
#include "lanelet2_core/geometry/Polygon.h"
#include "lanelet2_core/geometry/RegulatoryElement.h"
Include dependency graph for LaneletMap.cpp:

Go to the source code of this file.

Classes

struct  std::hash< lanelet::ConstRuleParameter >
 
struct  lanelet::PrimitiveLayer< T >::Tree
 
struct  lanelet::PrimitiveLayer< T >::Tree
 
struct  lanelet::UsageLookup< T >
 
struct  lanelet::UsageLookup< Area >
 
struct  lanelet::UsageLookup< Lanelet >
 
struct  lanelet::UsageLookup< Point3d >
 
struct  lanelet::UsageLookup< RegulatoryElementPtr >
 

Namespaces

 boost
 
 boost::geometry
 
 lanelet
 
 lanelet::geometry
 
 lanelet::utils
 
 std
 

Macros

#define INSTANCIATE_CONST_FIND_NEAREST(PRIM, CPRIM)   template std::vector<std::pair<double, CPRIM>> findNearest<PRIM>(const PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
 
#define INSTANCIATE_FIND_NEAREST(PRIM)   template std::vector<std::pair<double, PRIM>> findNearest<PRIM>(PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
 
#define LANELET_LAYER_DEFINITION
 

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)
 
template<>
bool boost::geometry::equals< lanelet::LineString3d, lanelet::LineString3d > (const lanelet::LineString3d &geometry1, const lanelet::LineString3d &geometry2)
 
template<>
bool boost::geometry::equals< lanelet::Polygon3d, lanelet::Polygon3d > (const lanelet::Polygon3d &geometry1, const lanelet::Polygon3d &geometry2)
 
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)
 
template std::vector< ConstLayerPrimitive< Lanelet > > lanelet::utils::findUsages< Lanelet > (const PrimitiveLayer< Lanelet > &, Id)
 
template std::vector< ConstLayerPrimitive< LineString3d > > lanelet::utils::findUsages< LineString3d > (const PrimitiveLayer< LineString3d > &, Id)
 
template std::vector< ConstLayerPrimitive< Polygon3d > > lanelet::utils::findUsages< Polygon3d > (const PrimitiveLayer< Polygon3d > &, Id)
 
template std::vector< ConstLayerPrimitive< RegulatoryElementPtr > > lanelet::utils::findUsages< RegulatoryElementPtr > (const PrimitiveLayer< RegulatoryElementPtr > &, 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...
 
 lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST (Area, ConstArea)
 
 lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST (Lanelet, ConstLanelet)
 
 lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST (LineString3d, ConstLineString3d)
 
 lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST (Point3d, ConstPoint3d)
 
 lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST (Polygon3d, ConstPolygon3d)
 
 lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST (RegulatoryElementPtr, RegulatoryElementConstPtr)
 
 lanelet::geometry::INSTANCIATE_FIND_NEAREST (Area)
 
 lanelet::geometry::INSTANCIATE_FIND_NEAREST (Lanelet)
 
 lanelet::geometry::INSTANCIATE_FIND_NEAREST (LineString3d)
 
 lanelet::geometry::INSTANCIATE_FIND_NEAREST (Point3d)
 
 lanelet::geometry::INSTANCIATE_FIND_NEAREST (Polygon3d)
 
 lanelet::geometry::INSTANCIATE_FIND_NEAREST (RegulatoryElementPtr)
 
void lanelet::utils::registerId (Id id)
 

Macro Definition Documentation

◆ INSTANCIATE_CONST_FIND_NEAREST

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

Definition at line 1002 of file LaneletMap.cpp.

◆ INSTANCIATE_FIND_NEAREST

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

Definition at line 1000 of file LaneletMap.cpp.

◆ LANELET_LAYER_DEFINITION

#define LANELET_LAYER_DEFINITION

Definition at line 1 of file LaneletMap.cpp.

Variable Documentation

◆ id

Id id {InvalId}

Definition at line 63 of file LaneletMap.cpp.

◆ map_

LaneletMap* map_
private

Definition at line 139 of file LaneletMap.cpp.

◆ n_

size_t n_
private

Definition at line 962 of file LaneletMap.cpp.

◆ values_

std::vector<std::pair<double, T> > values_
private

Definition at line 961 of file LaneletMap.cpp.



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