Go to the documentation of this file.
2 #include <boost/units/physical_dimensions/acceleration.hpp>
3 #include <boost/units/physical_dimensions/velocity.hpp>
4 #include <boost/units/quantity.hpp>
5 #include <boost/units/systems/si/base.hpp>
200 using Ids = std::vector<Id>;
204 using MPS = boost::units::unit<boost::units::velocity_dimension, boost::units::si::system>;
205 using MPS2 = boost::units::unit<boost::units::acceleration_dimension, boost::units::si::system>;
std::vector< CompoundHybridPolygon3d > CompoundHybridPolygons3d
constexpr Id InvalId
indicates a primitive that is not part of a map
std::vector< LaneletSequenceDataConstPtr > LaneletSequenceDataConstPtrs
std::vector< RegulatoryElementDataPtr > RegulatoryElementDataPtrs
std::vector< ConstLineString3d > ConstLineStrings3d
units::MPSQuantity Velocity
std::vector< CompoundLineStringDataPtr > CompoundLineStringDataPtrs
std::vector< LineString3d > LineStrings3d
units::MPS2Quantity Acceleration
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
A hybrid compound linestring in 2d (returns BasicPoint2d)
A GenericRegulatoryElement can hold any parameters.
std::vector< RegulatoryElementPtr > RegulatoryElementPtrs
std::vector< BasicPolygon2d > BasicPolygons2d
std::vector< LineString2d > LineStrings2d
std::vector< LaneletSubmapConstPtr > LaneletSubmapConstPtrs
Data container for all RegulatoryElement types.
Common data management class for all Lanelet-Typed objects.
Combines multiple linestrings to one polygon in 3d.
std::shared_ptr< LaneletMap > LaneletMapPtr
std::shared_ptr< const CompoundLineStringData > CompoundLineStringDataConstPtr
std::vector< PointDataConstPtr > PointDataConstPtrs
std::vector< LaneletMapPtr > LaneletMapPtrs
std::shared_ptr< LaneletSequenceData > LaneletSequenceDataPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
std::shared_ptr< CompoundLineStringData > CompoundLineStringDataPtr
A collection of Lanelets.
A const (i.e. immutable) Area.
std::shared_ptr< const LaneletSequenceData > LaneletSequenceDataConstPtr
Polygon with access to primitive points.
An object that can either refer to a lanelet or an area.
std::shared_ptr< const RegulatoryElementData > RegulatoryElementDataConstPtr
std::vector< CompoundPolygon2d > CompoundPolygons2d
boost::units::unit< boost::units::velocity_dimension, boost::units::si::system > MPS
std::vector< AreaDataPtr > AreaDataPtrs
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
std::vector< BasicPolygonWithHoles3d > BasicPolygonsWithHoles3d
boost::units::unit< boost::units::acceleration_dimension, boost::units::si::system > MPS2
std::shared_ptr< LineStringData > LineStringDataPtr
An immutable clockwise oriented, open (ie start point != end point) polygon in 3d.
std::vector< ConstHybridPolygon2d > ConstHybridPolygons2d
std::vector< ConstPolygon3d > ConstPolygons3d
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
std::weak_ptr< LaneletData > LaneletDataptr
std::shared_ptr< LaneletSubmap > LaneletSubmapPtr
std::vector< Lanelet > Lanelets
A general rule or limitation for a lanelet (abstract base class)
std::vector< LaneletDataPtr > LaneletDataPtrs
Creates regulatory elements based on their type.
A Linestring that returns BasicPoint2d instead of Point2d.
A Compound linestring in 3d (returns Point3d)
std::vector< LaneletMapConstPtr > LaneletMapConstPtrs
A normal 2d linestring with immutable data.
std::vector< CompoundLineString3d > CompoundLineStrings3d
An mutable clockwise oriented, open (ie start point != end point) polygon in 2d.
A (basic) 2d polygon with holes inside.
boost::units::quantity< MPS > MPSQuantity
Famous Area class that represents a basic area as element of the map.
std::vector< PointDataPtr > PointDataPtrs
std::vector< Polygon3d > Polygons3d
A normal 2d linestring with mutable data.
std::unique_ptr< LaneletMap > LaneletMapUPtr
std::shared_ptr< const PointData > PointDataConstPtr
std::shared_ptr< const AreaData > AreaDataConstPtr
std::vector< ConstPolygon2d > ConstPolygons2d
Basic element for accessing and managing the elements of a map.
The famous (mutable) lanelet class.
std::weak_ptr< AreaData > AreaDataptr
std::vector< GPSPoint > GPSPoints
std::vector< Point3d > Points3d
std::vector< AreaDataConstPtr > AreaDataConstPtrs
used internally by RegulatoryElements to avoid cyclic dependencies.
A hybrid compound linestring in 3d (returns BasicPoint3d)
std::unique_ptr< const LaneletSubmap > LaneletSubmapConstUPtr
Primitive 3d polygon with basic points.
Combines multiple linestrings to one polygon in 2d that returns BasicPoint2d.
std::shared_ptr< const LaneletData > LaneletDataConstPtr
Combines multiple linestrings to one polygon in 2d.
std::vector< CompoundHybridPolygon2d > CompoundHybridPolygons2d
std::vector< PrimitiveDataConstPtr > PrimitiveDataConstPtrs
std::shared_ptr< const PrimitiveData > PrimitiveDataConstPtr
Common data object for all CompoundLineStrings.
std::weak_ptr< const LaneletData > LaneletDataConstWptr
std::vector< PrimitiveDataPtr > PrimitiveDataPtrs
Common data management class for all Area-Typed objects.
std::vector< CompoundLineStringDataConstPtr > CompoundLineStringDataConstPtrs
std::shared_ptr< const LineStringData > LineStringDataConstPtr
std::vector< LaneletDataConstPtr > LaneletDataConstPtrs
std::vector< ConstLineString2d > ConstLineStrings2d
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
std::shared_ptr< PointData > PointDataPtr
std::vector< ConstPoint2d > ConstPoints2d
std::vector< BasicPolygonWithHoles2d > BasicPolygonsWithHoles2d
std::vector< RegulatoryElementDataConstPtr > RegulatoryElementDataConstPtrs
An immutable clockwise oriented, open (ie start point != end point) polygon in 2d.
Polygon with access to primitive points.
std::vector< Area > Areas
std::shared_ptr< AreaData > AreaDataPtr
std::vector< LaneletSubmapPtr > LaneletSubmapPtrs
std::shared_ptr< LaneletData > LaneletDataPtr
std::vector< LaneletSequence > LaneletSequences
std::vector< BasicPolygon3d > BasicPolygons3d
A LaneletSubmap only contains the elemets that have be expleicitly added to it.
std::vector< LaneletSequenceDataPtr > LaneletSequenceDataPtrs
A Compound linestring in 2d (returns Point2d)
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
A normal 3d linestring with immutable data.
A mutable clockwise oriented, open (ie start point != end point) polygon in 3d.
std::vector< LineStringDataPtr > LineStringDataPtrs
std::shared_ptr< const LaneletSubmap > LaneletSubmapConstPtr
std::vector< Point2d > Points2d
std::vector< CompoundPolygon3d > CompoundPolygons3d
std::vector< ConstPoint3d > ConstPoints3d
std::unique_ptr< LaneletSubmap > LaneletSubmapUPtr
std::unique_ptr< const LaneletMap > LaneletMapConstUPtr
Common data management class for LaneletSequences.
A Linestring that returns BasicPoint3d instead of Point3d.
used internally by RegulatoryElements to avoid cyclic dependencies.
std::vector< CompoundHybridLineString3d > CompoundHybridLineStrings3d
A (basic) 2d polygon with holes inside.
std::shared_ptr< PrimitiveData > PrimitiveDataPtr
std::vector< Polygon2d > Polygons2d
std::vector< ConstArea > ConstAreas
std::vector< CompoundHybridLineString2d > CompoundHybridLineStrings2d
A normal 3d linestring with mutable data.
std::vector< LaneletDataConstWptr > LaneletDataConstWptrs
boost::units::quantity< MPS2 > MPS2Quantity
std::vector< ConstHybridLineString2d > ConstHybridLineStrings2d
Primitive 2d polygon with basic points.
std::vector< ConstHybridLineString3d > ConstHybridLineStrings3d
std::vector< ConstLanelet > ConstLanelets
Combines multiple linestrings to one polygon in 3d that returns BasicPoint3d.
std::vector< CompoundLineString2d > CompoundLineStrings2d
std::vector< LineStringDataConstPtr > LineStringDataConstPtrs
std::vector< ConstHybridPolygon3d > ConstHybridPolygons3d
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52