Go to the documentation of this file.
3 #include <unordered_map>
43 using Map = std::unordered_map<Id, T>;
256 #ifndef LANELET_LAYER_DEFINITION
343 return laneletLayer.empty() && areaLayer.empty() && regulatoryElementLayer.empty() && polygonLayer.empty() &&
344 lineStringLayer.empty() && pointLayer.empty();
349 return laneletLayer.size() + areaLayer.size() + regulatoryElementLayer.size() + polygonLayer.size() +
350 lineStringLayer.size() + pointLayer.size();
503 template <
typename PrimitiveT>
541 template <
typename PrimitiveT>
550 template <
typename T>
552 using Type =
typename T::PrimitiveT;
554 template <
typename T>
556 using Type =
typename T::ConstPrimitiveT;
559 template <
typename T>
578 template <
typename PrimT>
580 template <
typename PrimT>
584 #ifndef LANELET_LAYER_DEFINITION
587 #define EXTERN_FIND_NEAREST(PRIM) extern template std::vector<std::pair<double, PRIM>> findNearest(PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
589 #define EXTERN_CONST_FIND_NEAREST(PRIM) extern template std::vector<std::pair<double, traits::ConstPrimitiveType<PRIM>>> findNearest(const PrimitiveLayer<PRIM>&, const BasicPoint2d&, unsigned)
603 #undef EXTERN_FIND_NEAREST
604 #undef EXTERN_CONST_FIND_NEAREST
LaneletLayer laneletLayer
access to the lanelets within this map
LaneletSubmapConstUPtr createConstSubmap(const ConstLanelets &fromLanelets, const ConstAreas &fromAreas)
std::vector< LineString3d > LineStrings3d
ConstPrimitiveVec search(const BoundingBox2d &area) const
searches for elements within a search area
OptPrimitiveT nearestUntil(const Point2d &point, const SearchFunction &func)
LineStringLayer lineStringLayer
access to the lineStrings
friend class LaneletMapLayers
Map elements_
the list of elements in this layer
AreaLayer areaLayer
access to areas
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
LaneletSubmap & operator=(LaneletMap &&rhs)
std::vector< ConstPrimitiveT > ConstPrimitiveVec
PointLayer pointLayer
access to the points
LaneletMapUPtr createMap(const Lanelets &fromLanelets, const Areas &fromAreas)
Id getId()
returns a unique id by incrementing a counter each time this is called.
bool empty() const noexcept
Returns whether all layers of this object are empty.
ConstPrimitiveVec nearest(const BasicPoint2d &point, unsigned n) const
search for the n nearest elements to a point
PolygonLayer polygonLayer
access to the polygons
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
LaneletSubmap(LaneletMap &&rhs) noexcept
Constructs a submap from a moved-from LaneletMap.
std::vector< Lanelet > Lanelets
A general rule or limitation for a lanelet (abstract base class)
friend class LaneletMapLayers
std::vector< PrimitiveT > PrimitiveVec
RegulatoryElementLayer regulatoryElementLayer
access to regElems
const BasicPoint2d & basicPoint2d() const noexcept
PrimitiveVec nearest(const Point2d &point, unsigned n)
void add(const PrimitiveT &element)
Axis-Aligned bounding box in 2d.
ConstPrimitiveT get(Id id) const
returns an element for this id if it exists
Famous Area class that represents a basic area as element of the map.
std::vector< Polygon3d > Polygons3d
std::unique_ptr< LaneletMap > LaneletMapUPtr
ConstPrimitiveVec nearest(const Point2d &point, unsigned n) const
Basic element for accessing and managing the elements of a map.
boost::optional< T > Optional
The famous (mutable) lanelet class.
LaneletMapLayers()=default
~PrimitiveLayer() noexcept
Optional< PrimitiveT > OptPrimitiveT
ConstAreas findUsagesInAreas(const LaneletMapLayers &map, const ConstPoint3d &p)
const_iterator find(Id id) const
find returns an iterator to an element if it exists
std::vector< Point3d > Points3d
const_iterator begin() const
iterator to beginning of the elements (not ordered by id!)
std::unordered_map< Id, RegulatoryElementPtr > Map
std::unique_ptr< const LaneletSubmap > LaneletSubmapConstUPtr
Each primitive in lanelet2 has its own layer in the map.
typename SearchBox< T >::Type SearchBoxT
traits::ConstPrimitiveType< RegulatoryElementPtr > ConstPrimitiveT
std::vector< boost::variant< ConstLanelet, ConstArea > > regelemObjects_
In order to not let lanelets/areas referenced by regelems get out of scope, we keep a reference to th...
friend class LaneletSubmap
OptConstPrimitiveT searchUntil(const BoundingBox2d &area, const ConstSearchFunction &func) const
searches within search area until a search function returns true.
OptConstPrimitiveT nearestUntil(const BasicPoint2d &point, const ConstSearchFunction &func) const
repeatedly calls a user-defined predicate until it returns true.
Specialized map layer for Area.
typename PrimitiveTraits< PrimitiveT >::ConstType ConstPrimitiveType
Utility for determinig the matching const type for a primitive.
bool empty() const
returns whether this layer contains something
std::function< bool(const internal::SearchBoxT< RegulatoryElementPtr > &box, const ConstPrimitiveT &prim)> ConstSearchFunction
Container for all layers of a lanelet map. Used by both LaneletMap and LaneletSubmap.
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
typename Owned< PrimitiveT >::Type OwnedT
#define EXTERN_FIND_NEAREST(PRIM)
std::vector< std::pair< double, traits::ConstPrimitiveType< PrimT > > > findNearest(const PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count)
PrimitiveLayer & operator=(const PrimitiveLayer &rhs)=delete
std::unique_ptr< Tree > tree_
Hides boost trees from you/the compiler.
LaneletMapConstUPtr createConstMap(const ConstLanelets &fromLanelets, const ConstAreas &fromAreas)
Specialized map layer for Lanelet.
std::vector< Area > Areas
size_t size() const
returns number of elements in this layer
bool exists(Id id) const
checks whether an element exists in this layer
ConstLanelets findUsagesInLanelets(const LaneletMapLayers &map, const ConstPoint3d &p)
LaneletSubmapUPtr createSubmap(const Lanelets &fromLanelets, const Areas &fromAreas)
A LaneletSubmap only contains the elemets that have be expleicitly added to it.
typename PrimitiveLayer< PrimitiveT >::ConstPrimitiveT ConstLayerPrimitive
typename T::PrimitiveT Type
RegulatoryElementPtr PrimitiveT
A mutable clockwise oriented, open (ie start point != end point) polygon in 3d.
friend class LaneletMapLayers
Optional< ConstPrimitiveT > OptConstPrimitiveT
std::unique_ptr< LaneletSubmap > LaneletSubmapUPtr
std::unique_ptr< const LaneletMap > LaneletMapConstUPtr
#define EXTERN_CONST_FIND_NEAREST(PRIM)
std::vector< ConstPrimitiveT > findUsages(const traits::ConstPrimitiveType< traits::OwnedT< PrimitiveT >> &primitive) const
finds usages of an owned type within this layer
PrimitiveLayer(const PrimitiveLayer &rhs)=delete
size_t size() const noexcept
Returns the total number of elements in all layers.
OptConstPrimitiveT nearestUntil(const ConstPoint2d &point, const ConstSearchFunction &func) const
std::vector< ConstArea > ConstAreas
A normal 3d linestring with mutable data.
const_iterator end() const
iterator to end of the elements
typename T::ConstPrimitiveT Type
auto basicPoint() noexcept
get a mutable reference to the 2d point data
std::vector< ConstLanelet > ConstLanelets
std::function< bool(const internal::SearchBoxT< RegulatoryElementPtr > &box, const PrimitiveT &prim)> SearchFunction
Id uniqueId() const
returns a unique id. it is guaranteed that the id is not used within this layer
friend class LaneletSubmap
friend class LaneletSubmap
typename LayerPrimitive< T >::Type LayerPrimitiveType
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52