Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
lanelet Namespace Reference

Namespaces

 detail
 
 geometry
 
 helper
 
 internal
 
 test_cases
 
 traits
 
 units
 
 utils
 

Classes

class  AllWayStop
 Defines an all way stop. These are a special form of right of way, where all lanelets have to yield, depending on the order of arrival and the route through the intersection. More...
 
struct  ArcCoordinates
 Describes a position in linestring coordinates. More...
 
class  Area
 Famous Area class that represents a basic area as element of the map. More...
 
class  AreaData
 Common data management class for all Area-Typed objects. More...
 
class  AreaLayer
 Specialized map layer for Area. More...
 
class  Attribute
 An attribute represents one value of a tag of a lanelet primitive. More...
 
struct  AttributeNamesString
 Lists which attribute strings are mapped to which enum value. More...
 
struct  AttributeValueString
 Common values for attributes are defined here. More...
 
class  BasicPolygon2d
 Primitive 2d polygon with basic points. More...
 
class  BasicPolygon3d
 Primitive 3d polygon with basic points. More...
 
class  BasicPolygonWithHoles2d
 A (basic) 2d polygon with holes inside. More...
 
class  BasicPolygonWithHoles3d
 A (basic) 2d polygon with holes inside. More...
 
class  BoundingBox2d
 Axis-Aligned bounding box in 2d. More...
 
class  CompoundHybridLineString2d
 A hybrid compound linestring in 2d (returns BasicPoint2d) More...
 
class  CompoundHybridLineString3d
 A hybrid compound linestring in 3d (returns BasicPoint3d) More...
 
class  CompoundHybridPolygon2d
 Combines multiple linestrings to one polygon in 2d that returns BasicPoint2d. More...
 
class  CompoundHybridPolygon3d
 Combines multiple linestrings to one polygon in 3d that returns BasicPoint3d. More...
 
class  CompoundLineString2d
 A Compound linestring in 2d (returns Point2d) More...
 
class  CompoundLineString3d
 A Compound linestring in 3d (returns Point3d) More...
 
class  CompoundLineStringData
 Common data object for all CompoundLineStrings. More...
 
class  CompoundLineStringImpl
 A collection of lineStrings that act as one line string. More...
 
class  CompoundPolygon2d
 Combines multiple linestrings to one polygon in 2d. More...
 
class  CompoundPolygon3d
 Combines multiple linestrings to one polygon in 3d. More...
 
class  ConstArea
 A const (i.e. immutable) Area. More...
 
class  ConstHybridLineString2d
 A Linestring that returns BasicPoint2d instead of Point2d. More...
 
class  ConstHybridLineString3d
 A Linestring that returns BasicPoint3d instead of Point3d. More...
 
class  ConstHybridPolygon2d
 Polygon with access to primitive points. More...
 
class  ConstHybridPolygon3d
 Polygon with access to primitive points. More...
 
class  ConstLanelet
 An immutable lanelet. More...
 
class  ConstLaneletOrArea
 An object that can either refer to a lanelet or an area. More...
 
struct  ConstLaneletWithStopLine
 
class  ConstLineString2d
 A normal 2d linestring with immutable data. More...
 
class  ConstLineString3d
 A normal 3d linestring with immutable data. More...
 
class  ConstLineStringImpl
 Implementation template class that is common to all LineStrings. More...
 
class  ConstLineStringOrPolygon3d
 This class holds either a ConstLineString3d or a ConstPolygon3d. More...
 
class  ConstPoint2d
 An immutable 2d point. More...
 
class  ConstPoint3d
 An immutable 3d point. More...
 
class  ConstPolygon2d
 An immutable clockwise oriented, open (ie start point != end point) polygon in 2d. More...
 
class  ConstPolygon3d
 An immutable clockwise oriented, open (ie start point != end point) polygon in 3d. More...
 
class  ConstPrimitive
 Basic Primitive class for all primitives of lanelet2. More...
 
class  ConstWeakArea
 used internally by RegulatoryElements to avoid cyclic dependencies. More...
 
class  ConstWeakLanelet
 
class  GenericRegulatoryElement
 A GenericRegulatoryElement can hold any parameters. More...
 
class  GeometryError
 Thrown when a geometric operation is not valid. More...
 
class  GPSPoint
 A raw GPS point. More...
 
struct  HashBase
 
class  HybridMap
 A hybrid map is just like a normal map with keys as string, but elements can also be accessed using an enum for the keys. This is much faster than using strings for the lookup. More...
 
class  InvalidInputError
 Thrown when a function was called with invalid input arguments. More...
 
class  InvalidObjectStateError
 Thrown when the state of a lanelet object is invalid E.g. when an linestring has no points or member pointers are NULL. More...
 
class  Lanelet
 The famous (mutable) lanelet class. More...
 
class  LaneletData
 Common data management class for all Lanelet-Typed objects. More...
 
class  LaneletError
 Generic lanelet error class. All errors lanelet2 will throw derive from this type. More...
 
class  LaneletLayer
 Specialized map layer for Lanelet. More...
 
class  LaneletMap
 Basic element for accessing and managing the elements of a map. More...
 
class  LaneletMapLayers
 Container for all layers of a lanelet map. Used by both LaneletMap and LaneletSubmap. More...
 
class  LaneletMultiError
 Thrown when multiple errors occur at the same time. More...
 
class  LaneletSequence
 A collection of Lanelets. More...
 
class  LaneletSequenceData
 Common data management class for LaneletSequences. More...
 
class  LaneletSubmap
 A LaneletSubmap only contains the elemets that have be expleicitly added to it. More...
 
struct  LaneletWithStopLine
 
class  LineString2d
 A normal 2d linestring with mutable data. More...
 
class  LineString3d
 A normal 3d linestring with mutable data. More...
 
class  LineStringData
 
class  LineStringImpl
 Implementation template class that is common to all non-const types. More...
 
class  LineStringOrPolygon3d
 This class holds either a LineString3d or a Polygon3d. More...
 
class  LineStringOrPolygonBase
 Base class for objects that can either refer to linestrings or polygons. More...
 
class  NoSuchAttributeError
 Thrown when an attribute has been queried that does not exist. More...
 
class  NoSuchPrimitiveError
 Thrown when an element is not part of the map. More...
 
class  NullptrError
 SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usually checked at object construction). More...
 
struct  Participants
 parts of tag that have to be combined with either Participants:, OneWay: or SpeedLimit to generate an override. More...
 
class  Point2d
 A mutable 2d point. More...
 
class  Point3d
 A mutable 3d point. More...
 
class  PointData
 
class  Polygon2d
 An mutable clockwise oriented, open (ie start point != end point) polygon in 2d. More...
 
class  Polygon3d
 A mutable clockwise oriented, open (ie start point != end point) polygon in 3d. More...
 
class  Primitive
 Base class for all mutable Primitives of lanelet2. More...
 
class  PrimitiveData
 Common data class for all lanelet primitives. More...
 
class  PrimitiveLayer
 Each primitive in lanelet2 has its own layer in the map. More...
 
class  RegisterRegulatoryElement
 template class for registering new RegulatoryElements. More...
 
class  RegulatoryElement
 A general rule or limitation for a lanelet (abstract base class) More...
 
class  RegulatoryElementData
 Data container for all RegulatoryElement types. More...
 
class  RegulatoryElementFactory
 Creates regulatory elements based on their type. More...
 
class  RightOfWay
 Defines right of way restrictions. More...
 
struct  RoleNameString
 Lists which role strings are mapped to which enum value. More...
 
class  RuleParameterVisitor
 You can inherit from this visitor to perform an operation on each parameter of a regulatory element. More...
 
class  SpeedLimit
 Represents a speed limit that affects a lanelet. More...
 
class  TrafficLight
 Represents a traffic light restriction on the lanelet. More...
 
class  TrafficSign
 Expresses a generic traffic sign rule. More...
 
struct  TrafficSignsWithType
 Used as input argument to create TrafficSign regElem. More...
 
struct  UsageLookup
 
struct  UsageLookup< Area >
 
struct  UsageLookup< Lanelet >
 
struct  UsageLookup< Point3d >
 
struct  UsageLookup< RegulatoryElementPtr >
 
class  WeakArea
 used internally by RegulatoryElements to avoid cyclic dependencies. More...
 
class  WeakLanelet
 

Typedefs

using Acceleration = units::MPS2Quantity
 
using AreaDataConstPtr = std::shared_ptr< const AreaData >
 
using AreaDataConstPtrs = std::vector< AreaDataConstPtr >
 
using AreaDataPtr = std::shared_ptr< AreaData >
 
using AreaDataptr = std::weak_ptr< AreaData >
 
using AreaDataPtrs = std::vector< AreaDataPtr >
 
using Areas = std::vector< Area >
 
using AttributeMap = HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
 
using AttributeNamesItem = std::pair< const char *, const AttributeName >
 
using BasicLineString2d = BasicPoints2d
 
using BasicLineString3d = BasicPoints3d
 
using BasicPoint2d = Eigen::Matrix< double, 2, 1, Eigen::DontAlign >
 a simple 2d-point More...
 
using BasicPoint3d = Eigen::Vector3d
 a simple 3d-point More...
 
using BasicPoints2d = std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > >
 multiple simple 2d-points More...
 
using BasicPoints3d = std::vector< BasicPoint3d >
 multiple simple 3d-points More...
 
using BasicPolygons2d = std::vector< BasicPolygon2d >
 
using BasicPolygons3d = std::vector< BasicPolygon3d >
 
using BasicPolygonsWithHoles2d = std::vector< BasicPolygonWithHoles2d >
 
using BasicPolygonsWithHoles3d = std::vector< BasicPolygonWithHoles3d >
 
using BasicSegment2d = Segment< BasicPoint2d >
 
using BasicSegment3d = Segment< BasicPoint3d >
 
using BoundingBox3d = Eigen::AlignedBox3d
 Convenience type for an axis aligned bounding box in 3d. More...
 
using CompoundHybridLineStrings2d = std::vector< CompoundHybridLineString2d >
 
using CompoundHybridLineStrings3d = std::vector< CompoundHybridLineString3d >
 
using CompoundHybridPolygons2d = std::vector< CompoundHybridPolygon2d >
 
using CompoundHybridPolygons3d = std::vector< CompoundHybridPolygon3d >
 
using CompoundLineStringDataConstPtr = std::shared_ptr< const CompoundLineStringData >
 
using CompoundLineStringDataConstPtrs = std::vector< CompoundLineStringDataConstPtr >
 
using CompoundLineStringDataPtr = std::shared_ptr< CompoundLineStringData >
 
using CompoundLineStringDataPtrs = std::vector< CompoundLineStringDataPtr >
 
using CompoundLineStrings2d = std::vector< CompoundLineString2d >
 
using CompoundLineStrings3d = std::vector< CompoundLineString3d >
 
using CompoundPolygons2d = std::vector< CompoundPolygon2d >
 
using CompoundPolygons3d = std::vector< CompoundPolygon3d >
 
using ConstAreas = std::vector< ConstArea >
 
using ConstHybridLineStrings2d = std::vector< ConstHybridLineString2d >
 
using ConstHybridLineStrings3d = std::vector< ConstHybridLineString3d >
 
using ConstHybridPolygons2d = std::vector< ConstHybridPolygon2d >
 
using ConstHybridPolygons3d = std::vector< ConstHybridPolygon3d >
 
using ConstInnerBounds = std::vector< ConstLineStrings3d >
 
using ConstLaneletOrAreas = std::vector< ConstLaneletOrArea >
 
using ConstLanelets = std::vector< ConstLanelet >
 
using ConstLineStrings2d = std::vector< ConstLineString2d >
 
using ConstLineStrings3d = std::vector< ConstLineString3d >
 
using ConstLineStringsOrPolygons3d = std::vector< ConstLineStringOrPolygon3d >
 
using ConstPoints2d = std::vector< ConstPoint2d >
 
using ConstPoints3d = std::vector< ConstPoint3d >
 
using ConstPolygons2d = std::vector< ConstPolygon2d >
 
using ConstPolygons3d = std::vector< ConstPolygon3d >
 
using ConstRuleParameter = boost::variant< ConstPoint3d, ConstLineString3d, ConstPolygon3d, ConstWeakLanelet, ConstWeakArea >
 Const-version of the parameters. More...
 
using ConstRuleParameterMap = HybridMap< ConstRuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map >
 Rules are stored in a map internally (const version) More...
 
using ConstRuleParameters = std::vector< ConstRuleParameter >
 Const version for a range of rule parameters. More...
 
using ConstSegment2d = Segment< ConstPoint2d >
 
using ConstSegment3d = Segment< ConstPoint3d >
 
using GPSPoints = std::vector< GPSPoint >
 
using Id = int64_t
 
using Ids = std::vector< Id >
 
template<typename T , typename RetT >
using IfAr = std::enable_if_t< traits::isAreaT< T >(), RetT >
 
template<typename T , typename RetT >
using IfLL = std::enable_if_t< traits::isLaneletT< T >(), RetT >
 
template<typename T , typename RetT >
using IfLS = std::enable_if_t< traits::isLinestringT< T >(), RetT >
 
template<typename T1 , typename T2 , typename RetT >
using IfLS2 = std::enable_if_t< traits::isLinestringT< T1 >() &&traits::isLinestringT< T2 >(), RetT >
 
template<typename T , typename RetT >
using IfPoly = std::enable_if_t< traits::isPolygonT< T >(), RetT >
 
template<typename T , typename RetT >
using IfPT = std::enable_if_t< traits::isPointT< T >(), RetT >
 
template<typename T , typename RetT >
using IfRE = std::enable_if_t< traits::isRegulatoryElementT< T >(), RetT >
 
using InnerBounds = std::vector< LineStrings3d >
 
using LaneletDataConstPtr = std::shared_ptr< const LaneletData >
 
using LaneletDataConstPtrs = std::vector< LaneletDataConstPtr >
 
using LaneletDataConstWptr = std::weak_ptr< const LaneletData >
 
using LaneletDataConstWptrs = std::vector< LaneletDataConstWptr >
 
using LaneletDataPtr = std::shared_ptr< LaneletData >
 
using LaneletDataptr = std::weak_ptr< LaneletData >
 
using LaneletDataPtrs = std::vector< LaneletDataPtr >
 
using LaneletMapConstPtr = std::shared_ptr< const LaneletMap >
 
using LaneletMapConstPtrs = std::vector< LaneletMapConstPtr >
 
using LaneletMapConstUPtr = std::unique_ptr< const LaneletMap >
 
using LaneletMapPtr = std::shared_ptr< LaneletMap >
 
using LaneletMapPtrs = std::vector< LaneletMapPtr >
 
using LaneletMapUPtr = std::unique_ptr< LaneletMap >
 
using Lanelets = std::vector< Lanelet >
 
using LaneletSequenceDataConstPtr = std::shared_ptr< const LaneletSequenceData >
 
using LaneletSequenceDataConstPtrs = std::vector< LaneletSequenceDataConstPtr >
 
using LaneletSequenceDataPtr = std::shared_ptr< LaneletSequenceData >
 
using LaneletSequenceDataPtrs = std::vector< LaneletSequenceDataPtr >
 
using LaneletSequences = std::vector< LaneletSequence >
 
using LaneletSubmapConstPtr = std::shared_ptr< const LaneletSubmap >
 
using LaneletSubmapConstPtrs = std::vector< LaneletSubmapConstPtr >
 
using LaneletSubmapConstUPtr = std::unique_ptr< const LaneletSubmap >
 
using LaneletSubmapPtr = std::shared_ptr< LaneletSubmap >
 
using LaneletSubmapPtrs = std::vector< LaneletSubmapPtr >
 
using LaneletSubmapUPtr = std::unique_ptr< LaneletSubmap >
 
using LaneletsWithStopLines = std::vector< LaneletWithStopLine >
 
using LineStringDataConstPtr = std::shared_ptr< const LineStringData >
 
using LineStringDataConstPtrs = std::vector< LineStringDataConstPtr >
 
using LineStringDataPtr = std::shared_ptr< LineStringData >
 
using LineStringDataPtrs = std::vector< LineStringDataPtr >
 
using LineStringLayer = PrimitiveLayer< LineString3d >
 
using LineStrings2d = std::vector< LineString2d >
 
using LineStrings3d = std::vector< LineString3d >
 
using LineStringsOrPolygons3d = std::vector< LineStringOrPolygon3d >
 
using OptDistance = boost::optional< double >
 
template<typename T >
using Optional = boost::optional< T >
 
using PointDataConstPtr = std::shared_ptr< const PointData >
 
using PointDataConstPtrs = std::vector< PointDataConstPtr >
 
using PointDataPtr = std::shared_ptr< PointData >
 
using PointDataPtrs = std::vector< PointDataPtr >
 
using PointLayer = PrimitiveLayer< Point3d >
 
using Points2d = std::vector< Point2d >
 
using Points3d = std::vector< Point3d >
 
using PolygonLayer = PrimitiveLayer< Polygon3d >
 
using Polygons2d = std::vector< Polygon2d >
 
using Polygons3d = std::vector< Polygon3d >
 
using PrimitiveDataConstPtr = std::shared_ptr< const PrimitiveData >
 
using PrimitiveDataConstPtrs = std::vector< PrimitiveDataConstPtr >
 
using PrimitiveDataPtr = std::shared_ptr< PrimitiveData >
 
using PrimitiveDataPtrs = std::vector< PrimitiveDataPtr >
 
using RegulatoryElementConstPtr = std::shared_ptr< const RegulatoryElement >
 
using RegulatoryElementConstPtrs = std::vector< RegulatoryElementConstPtr >
 
using RegulatoryElementDataConstPtr = std::shared_ptr< const RegulatoryElementData >
 
using RegulatoryElementDataConstPtrs = std::vector< RegulatoryElementDataConstPtr >
 
using RegulatoryElementDataPtr = std::shared_ptr< RegulatoryElementData >
 
using RegulatoryElementDataPtrs = std::vector< RegulatoryElementDataPtr >
 
using RegulatoryElementLayer = PrimitiveLayer< RegulatoryElementPtr >
 
using RegulatoryElementPtr = std::shared_ptr< RegulatoryElement >
 
using RegulatoryElementPtrs = std::vector< RegulatoryElementPtr >
 
using RuleParameter = boost::variant< Point3d, LineString3d, Polygon3d, WeakLanelet, WeakArea >
 
using RuleParameterMap = HybridMap< RuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map >
 Rules are stored in a map internally. More...
 
using RuleParameters = std::vector< RuleParameter >
 Multiple parameters can have the same role in a rule (eg traffic_lights) More...
 
template<typename PointT >
using Segment = std::pair< PointT, PointT >
 
using Segment2d = Segment< Point2d >
 
using Segment3d = Segment< Point3d >
 
using Velocity = units::MPSQuantity
 

Enumerations

enum  AttributeName {
  AttributeName::Type, AttributeName::Subtype, AttributeName::OneWay, AttributeName::ParticipantVehicle,
  AttributeName::ParticipantPedestrian, AttributeName::SpeedLimit, AttributeName::Location, AttributeName::Dynamic
}
 Typical Attributes names within lanelet. More...
 
enum  LaneletType { LaneletType::OneWay, LaneletType::Bidirectional }
 
enum  ManeuverType { ManeuverType::Yield, ManeuverType::RightOfWay, ManeuverType::Unknown }
 Enum to distinguish maneuver types. More...
 
enum  RoleName {
  RoleName::Refers, RoleName::RefLine, RoleName::RightOfWay, RoleName::Yield,
  RoleName::Cancels, RoleName::CancelLine
}
 Typical role names within lanelet (for faster lookup) More...
 

Functions

template<>
Optional< std::string > Attribute::as< Optional< std::string > > () const
 
template<>
Optional< std::string > Attribute::as< std::string > () const
 
bool operator!= (const Attribute &lhs, const Attribute &rhs)
 
template<typename Point1T , typename Point2T >
bool operator!= (const CompoundLineStringImpl< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
template<typename Point1T , typename Point2T >
bool operator!= (const CompoundLineStringImpl< Point1T > &lhs, const std::vector< Point2T > &rhs)
 
bool operator!= (const ConstArea &lhs, const ConstArea &rhs)
 
bool operator!= (const ConstLanelet &lhs, const ConstLanelet &rhs)
 
bool operator!= (const ConstLaneletOrArea &lhs, const ConstLaneletOrArea &rhs)
 
template<typename LhsPointT , typename RhsPointT >
bool operator!= (const ConstLineStringImpl< LhsPointT > &lhs, const ConstLineStringImpl< RhsPointT > &rhs)
 
template<typename PointT >
bool operator!= (const ConstLineStringImpl< PointT > &lhs, const std::vector< PointT > &rhs)
 
bool operator!= (const ConstLineStringOrPolygon3d &lhs, const ConstLineStringOrPolygon3d &rhs)
 
bool operator!= (const ConstWeakArea &lhs, const ConstWeakArea &rhs)
 
bool operator!= (const ConstWeakLanelet &lhs, const ConstWeakLanelet &rhs)
 
bool operator!= (const LaneletSequence &lhs, const LaneletSequence &rhs)
 
bool operator!= (const LineStringOrPolygon3d &lhs, const LineStringOrPolygon3d &rhs)
 
template<typename Point1T , typename Point2T >
bool operator!= (const std::vector< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
template<typename PointT >
bool operator!= (const std::vector< PointT > &lhs, const ConstLineStringImpl< PointT > &rhs)
 
std::ostream & operator<< (std::ostream &stream, const Attribute &obj)
 
std::ostream & operator<< (std::ostream &stream, const AttributeMap &obj)
 
template<typename PointT >
std::ostream & operator<< (std::ostream &stream, const CompoundLineStringImpl< PointT > &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstArea &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLanelet &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLaneletOrArea &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLineString2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLineString3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLineStringOrPolygon3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPoint2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPoint3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPolygon2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPolygon3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const LaneletSequence &obj)
 
std::ostream & operator<< (std::ostream &stream, const LineStringOrPolygon3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const Point2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const Point3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const RegulatoryElement &obj)
 
template<typename Value , typename Enum , const std::pair< const char *, const Enum > Lookup>
std::ostream & operator<< (std::ostream &stream, HybridMap< Value, Enum, Lookup > map)
 
bool operator== (const Attribute &lhs, const Attribute &rhs)
 
template<typename Point1T , typename Point2T >
bool operator== (const CompoundLineStringImpl< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
template<typename Point1T , typename Point2T >
bool operator== (const CompoundLineStringImpl< Point1T > &lhs, const std::vector< Point2T > &rhs)
 
bool operator== (const ConstArea &lhs, const ConstArea &rhs)
 
bool operator== (const ConstLanelet &lhs, const ConstLanelet &rhs)
 
bool operator== (const ConstLaneletOrArea &lhs, const ConstLaneletOrArea &rhs)
 
template<typename LhsPointT , typename RhsPointT >
bool operator== (const ConstLineStringImpl< LhsPointT > &lhs, const ConstLineStringImpl< RhsPointT > &rhs)
 
template<typename PointT >
bool operator== (const ConstLineStringImpl< PointT > &lhs, const std::vector< PointT > &rhs)
 
bool operator== (const ConstLineStringOrPolygon3d &lhs, const ConstLineStringOrPolygon3d &rhs)
 
bool operator== (const ConstWeakArea &lhs, const ConstWeakArea &rhs)
 
bool operator== (const ConstWeakLanelet &lhs, const ConstWeakLanelet &rhs)
 
bool operator== (const LaneletSequence &lhs, const LaneletSequence &rhs)
 
bool operator== (const LineStringOrPolygon3d &lhs, const LineStringOrPolygon3d &rhs)
 
template<typename Point1T , typename Point2T >
bool operator== (const std::vector< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
template<typename PointT >
bool operator== (const std::vector< PointT > &lhs, const ConstLineStringImpl< PointT > &rhs)
 

Variables

static RegisterRegulatoryElement< GenericRegulatoryElementgenRegelem
 
constexpr Id InvalId = 0
 indicates a primitive that is not part of a map More...
 
static RegisterRegulatoryElement< AllWayStopregAllWayStop
 
static RegisterRegulatoryElement< RightOfWayregRightOfWay
 
static RegisterRegulatoryElement< SpeedLimitregSpeedLimit
 
static RegisterRegulatoryElement< TrafficLightregTraffic
 
static RegisterRegulatoryElement< TrafficSignregTrafficSign
 

Detailed Description

basic namespace for everything in lanelet2

Typedef Documentation

◆ Acceleration

Definition at line 211 of file Forward.h.

◆ AreaDataConstPtr

using lanelet::AreaDataConstPtr = typedef std::shared_ptr<const AreaData>

Definition at line 132 of file Forward.h.

◆ AreaDataConstPtrs

using lanelet::AreaDataConstPtrs = typedef std::vector<AreaDataConstPtr>

Definition at line 134 of file Forward.h.

◆ AreaDataPtr

using lanelet::AreaDataPtr = typedef std::shared_ptr<AreaData>

Definition at line 130 of file Forward.h.

◆ AreaDataptr

using lanelet::AreaDataptr = typedef std::weak_ptr<AreaData>

Definition at line 131 of file Forward.h.

◆ AreaDataPtrs

using lanelet::AreaDataPtrs = typedef std::vector<AreaDataPtr>

Definition at line 133 of file Forward.h.

◆ Areas

using lanelet::Areas = typedef std::vector<Area>

Definition at line 125 of file Forward.h.

◆ AttributeMap

Definition at line 371 of file Attribute.h.

◆ AttributeNamesItem

using lanelet::AttributeNamesItem = typedef std::pair<const char*, const AttributeName>

Definition at line 196 of file Attribute.h.

◆ BasicLineString2d

Definition at line 14 of file primitives/LineString.h.

◆ BasicLineString3d

Definition at line 15 of file primitives/LineString.h.

◆ BasicPoint2d

using lanelet::BasicPoint2d = typedef Eigen::Matrix<double, 2, 1, Eigen::DontAlign>

a simple 2d-point

Definition at line 20 of file primitives/Point.h.

◆ BasicPoint3d

using lanelet::BasicPoint3d = typedef Eigen::Vector3d

a simple 3d-point

Definition at line 19 of file primitives/Point.h.

◆ BasicPoints2d

using lanelet::BasicPoints2d = typedef std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >

multiple simple 2d-points

Definition at line 22 of file primitives/Point.h.

◆ BasicPoints3d

using lanelet::BasicPoints3d = typedef std::vector<BasicPoint3d>

multiple simple 3d-points

Definition at line 23 of file primitives/Point.h.

◆ BasicPolygons2d

using lanelet::BasicPolygons2d = typedef std::vector<BasicPolygon2d>

Definition at line 153 of file Forward.h.

◆ BasicPolygons3d

using lanelet::BasicPolygons3d = typedef std::vector<BasicPolygon3d>

Definition at line 154 of file Forward.h.

◆ BasicPolygonsWithHoles2d

Definition at line 162 of file Forward.h.

◆ BasicPolygonsWithHoles3d

Definition at line 161 of file Forward.h.

◆ BasicSegment2d

Definition at line 24 of file primitives/LineString.h.

◆ BasicSegment3d

Definition at line 25 of file primitives/LineString.h.

◆ BoundingBox3d

using lanelet::BoundingBox3d = typedef Eigen::AlignedBox3d

Convenience type for an axis aligned bounding box in 3d.

Can be used as Eigen::AlignedBox2d and as boost::geometry::Box.

Definition at line 283 of file primitives/BoundingBox.h.

◆ CompoundHybridLineStrings2d

Definition at line 78 of file Forward.h.

◆ CompoundHybridLineStrings3d

Definition at line 79 of file Forward.h.

◆ CompoundHybridPolygons2d

Definition at line 88 of file Forward.h.

◆ CompoundHybridPolygons3d

Definition at line 89 of file Forward.h.

◆ CompoundLineStringDataConstPtr

using lanelet::CompoundLineStringDataConstPtr = typedef std::shared_ptr<const CompoundLineStringData>

Definition at line 67 of file Forward.h.

◆ CompoundLineStringDataConstPtrs

Definition at line 69 of file Forward.h.

◆ CompoundLineStringDataPtr

Definition at line 66 of file Forward.h.

◆ CompoundLineStringDataPtrs

Definition at line 68 of file Forward.h.

◆ CompoundLineStrings2d

Definition at line 76 of file Forward.h.

◆ CompoundLineStrings3d

Definition at line 77 of file Forward.h.

◆ CompoundPolygons2d

using lanelet::CompoundPolygons2d = typedef std::vector<CompoundPolygon2d>

Definition at line 87 of file Forward.h.

◆ CompoundPolygons3d

using lanelet::CompoundPolygons3d = typedef std::vector<CompoundPolygon3d>

Definition at line 86 of file Forward.h.

◆ ConstAreas

using lanelet::ConstAreas = typedef std::vector<ConstArea>

Definition at line 126 of file Forward.h.

◆ ConstHybridLineStrings2d

Definition at line 61 of file Forward.h.

◆ ConstHybridLineStrings3d

Definition at line 62 of file Forward.h.

◆ ConstHybridPolygons2d

Definition at line 155 of file Forward.h.

◆ ConstHybridPolygons3d

Definition at line 156 of file Forward.h.

◆ ConstInnerBounds

using lanelet::ConstInnerBounds = typedef std::vector<ConstLineStrings3d>

Definition at line 39 of file primitives/Area.h.

◆ ConstLaneletOrAreas

using lanelet::ConstLaneletOrAreas = typedef std::vector<ConstLaneletOrArea>

Definition at line 138 of file Forward.h.

◆ ConstLanelets

using lanelet::ConstLanelets = typedef std::vector<ConstLanelet>

Definition at line 114 of file Forward.h.

◆ ConstLineStrings2d

using lanelet::ConstLineStrings2d = typedef std::vector<ConstLineString2d>

Definition at line 60 of file Forward.h.

◆ ConstLineStrings3d

using lanelet::ConstLineStrings3d = typedef std::vector<ConstLineString3d>

Definition at line 58 of file Forward.h.

◆ ConstLineStringsOrPolygons3d

Definition at line 133 of file LineStringOrPolygon.h.

◆ ConstPoints2d

using lanelet::ConstPoints2d = typedef std::vector<ConstPoint2d>

Definition at line 37 of file Forward.h.

◆ ConstPoints3d

using lanelet::ConstPoints3d = typedef std::vector<ConstPoint3d>

Definition at line 35 of file Forward.h.

◆ ConstPolygons2d

using lanelet::ConstPolygons2d = typedef std::vector<ConstPolygon2d>

Definition at line 152 of file Forward.h.

◆ ConstPolygons3d

using lanelet::ConstPolygons3d = typedef std::vector<ConstPolygon3d>

Definition at line 150 of file Forward.h.

◆ ConstRuleParameter

Const-version of the parameters.

Definition at line 94 of file primitives/RegulatoryElement.h.

◆ ConstRuleParameterMap

Rules are stored in a map internally (const version)

Definition at line 130 of file primitives/RegulatoryElement.h.

◆ ConstRuleParameters

using lanelet::ConstRuleParameters = typedef std::vector<ConstRuleParameter>

Const version for a range of rule parameters.

Definition at line 124 of file primitives/RegulatoryElement.h.

◆ ConstSegment2d

Definition at line 21 of file primitives/LineString.h.

◆ ConstSegment3d

Definition at line 23 of file primitives/LineString.h.

◆ GPSPoints

using lanelet::GPSPoints = typedef std::vector<GPSPoint>

Definition at line 41 of file Forward.h.

◆ Id

using lanelet::Id = typedef int64_t

Definition at line 198 of file Forward.h.

◆ Ids

using lanelet::Ids = typedef std::vector<Id>

Definition at line 200 of file Forward.h.

◆ IfAr

template<typename T , typename RetT >
using lanelet::IfAr = typedef std::enable_if_t<traits::isAreaT<T>(), RetT>

Definition at line 364 of file primitives/Area.h.

◆ IfLL

template<typename T , typename RetT >
using lanelet::IfLL = typedef std::enable_if_t<traits::isLaneletT<T>(), RetT>

Definition at line 387 of file primitives/Lanelet.h.

◆ IfLS

template<typename T , typename RetT >
using lanelet::IfLS = typedef std::enable_if_t<traits::isLinestringT<T>(), RetT>

Definition at line 771 of file primitives/LineString.h.

◆ IfLS2

template<typename T1 , typename T2 , typename RetT >
using lanelet::IfLS2 = typedef std::enable_if_t<traits::isLinestringT<T1>() && traits::isLinestringT<T2>(), RetT>

Definition at line 774 of file primitives/LineString.h.

◆ IfPoly

template<typename T , typename RetT >
using lanelet::IfPoly = typedef std::enable_if_t<traits::isPolygonT<T>(), RetT>

Definition at line 428 of file primitives/Polygon.h.

◆ IfPT

template<typename T , typename RetT >
using lanelet::IfPT = typedef std::enable_if_t<traits::isPointT<T>(), RetT>

Definition at line 335 of file primitives/Point.h.

◆ IfRE

template<typename T , typename RetT >
using lanelet::IfRE = typedef std::enable_if_t<traits::isRegulatoryElementT<T>(), RetT>

Definition at line 508 of file primitives/RegulatoryElement.h.

◆ InnerBounds

using lanelet::InnerBounds = typedef std::vector<LineStrings3d>

Definition at line 38 of file primitives/Area.h.

◆ LaneletDataConstPtr

using lanelet::LaneletDataConstPtr = typedef std::shared_ptr<const LaneletData>

Definition at line 102 of file Forward.h.

◆ LaneletDataConstPtrs

using lanelet::LaneletDataConstPtrs = typedef std::vector<LaneletDataConstPtr>

Definition at line 105 of file Forward.h.

◆ LaneletDataConstWptr

using lanelet::LaneletDataConstWptr = typedef std::weak_ptr<const LaneletData>

Definition at line 103 of file Forward.h.

◆ LaneletDataConstWptrs

Definition at line 106 of file Forward.h.

◆ LaneletDataPtr

using lanelet::LaneletDataPtr = typedef std::shared_ptr<LaneletData>

Definition at line 100 of file Forward.h.

◆ LaneletDataptr

using lanelet::LaneletDataptr = typedef std::weak_ptr<LaneletData>

Definition at line 101 of file Forward.h.

◆ LaneletDataPtrs

using lanelet::LaneletDataPtrs = typedef std::vector<LaneletDataPtr>

Definition at line 104 of file Forward.h.

◆ LaneletMapConstPtr

using lanelet::LaneletMapConstPtr = typedef std::shared_ptr<const LaneletMap>

Definition at line 168 of file Forward.h.

◆ LaneletMapConstPtrs

using lanelet::LaneletMapConstPtrs = typedef std::vector<LaneletMapConstPtr>

Definition at line 171 of file Forward.h.

◆ LaneletMapConstUPtr

using lanelet::LaneletMapConstUPtr = typedef std::unique_ptr<const LaneletMap>

Definition at line 169 of file Forward.h.

◆ LaneletMapPtr

using lanelet::LaneletMapPtr = typedef std::shared_ptr<LaneletMap>

Definition at line 166 of file Forward.h.

◆ LaneletMapPtrs

using lanelet::LaneletMapPtrs = typedef std::vector<LaneletMapPtr>

Definition at line 170 of file Forward.h.

◆ LaneletMapUPtr

using lanelet::LaneletMapUPtr = typedef std::unique_ptr<LaneletMap>

Definition at line 167 of file Forward.h.

◆ Lanelets

using lanelet::Lanelets = typedef std::vector<Lanelet>

Definition at line 113 of file Forward.h.

◆ LaneletSequenceDataConstPtr

using lanelet::LaneletSequenceDataConstPtr = typedef std::shared_ptr<const LaneletSequenceData>

Definition at line 94 of file Forward.h.

◆ LaneletSequenceDataConstPtrs

Definition at line 96 of file Forward.h.

◆ LaneletSequenceDataPtr

using lanelet::LaneletSequenceDataPtr = typedef std::shared_ptr<LaneletSequenceData>

Definition at line 93 of file Forward.h.

◆ LaneletSequenceDataPtrs

Definition at line 95 of file Forward.h.

◆ LaneletSequences

using lanelet::LaneletSequences = typedef std::vector<LaneletSequence>

Definition at line 118 of file Forward.h.

◆ LaneletSubmapConstPtr

using lanelet::LaneletSubmapConstPtr = typedef std::shared_ptr<const LaneletSubmap>

Definition at line 177 of file Forward.h.

◆ LaneletSubmapConstPtrs

Definition at line 180 of file Forward.h.

◆ LaneletSubmapConstUPtr

using lanelet::LaneletSubmapConstUPtr = typedef std::unique_ptr<const LaneletSubmap>

Definition at line 178 of file Forward.h.

◆ LaneletSubmapPtr

using lanelet::LaneletSubmapPtr = typedef std::shared_ptr<LaneletSubmap>

Definition at line 175 of file Forward.h.

◆ LaneletSubmapPtrs

using lanelet::LaneletSubmapPtrs = typedef std::vector<LaneletSubmapPtr>

Definition at line 179 of file Forward.h.

◆ LaneletSubmapUPtr

using lanelet::LaneletSubmapUPtr = typedef std::unique_ptr<LaneletSubmap>

Definition at line 176 of file Forward.h.

◆ LaneletsWithStopLines

Definition at line 154 of file BasicRegulatoryElements.h.

◆ LineStringDataConstPtr

using lanelet::LineStringDataConstPtr = typedef std::shared_ptr<const LineStringData>

Definition at line 46 of file Forward.h.

◆ LineStringDataConstPtrs

Definition at line 48 of file Forward.h.

◆ LineStringDataPtr

using lanelet::LineStringDataPtr = typedef std::shared_ptr<LineStringData>

Definition at line 45 of file Forward.h.

◆ LineStringDataPtrs

using lanelet::LineStringDataPtrs = typedef std::vector<LineStringDataPtr>

Definition at line 47 of file Forward.h.

◆ LineStringLayer

Definition at line 306 of file LaneletMap.h.

◆ LineStrings2d

using lanelet::LineStrings2d = typedef std::vector<LineString2d>

Definition at line 59 of file Forward.h.

◆ LineStrings3d

using lanelet::LineStrings3d = typedef std::vector<LineString3d>

Definition at line 57 of file Forward.h.

◆ LineStringsOrPolygons3d

Definition at line 132 of file LineStringOrPolygon.h.

◆ OptDistance

using lanelet::OptDistance = typedef boost::optional<double>

Definition at line 14 of file Lanelet.cpp.

◆ Optional

template<typename T >
using lanelet::Optional = typedef boost::optional<T>

Definition at line 7 of file Optional.h.

◆ PointDataConstPtr

using lanelet::PointDataConstPtr = typedef std::shared_ptr<const PointData>

Definition at line 25 of file Forward.h.

◆ PointDataConstPtrs

using lanelet::PointDataConstPtrs = typedef std::vector<PointDataConstPtr>

Definition at line 27 of file Forward.h.

◆ PointDataPtr

using lanelet::PointDataPtr = typedef std::shared_ptr<PointData>

Definition at line 24 of file Forward.h.

◆ PointDataPtrs

using lanelet::PointDataPtrs = typedef std::vector<PointDataPtr>

Definition at line 26 of file Forward.h.

◆ PointLayer

Definition at line 307 of file LaneletMap.h.

◆ Points2d

using lanelet::Points2d = typedef std::vector<Point2d>

Definition at line 36 of file Forward.h.

◆ Points3d

using lanelet::Points3d = typedef std::vector<Point3d>

Definition at line 34 of file Forward.h.

◆ PolygonLayer

Definition at line 305 of file LaneletMap.h.

◆ Polygons2d

using lanelet::Polygons2d = typedef std::vector<Polygon2d>

Definition at line 151 of file Forward.h.

◆ Polygons3d

using lanelet::Polygons3d = typedef std::vector<Polygon3d>

Definition at line 149 of file Forward.h.

◆ PrimitiveDataConstPtr

using lanelet::PrimitiveDataConstPtr = typedef std::shared_ptr<const PrimitiveData>

Definition at line 18 of file Forward.h.

◆ PrimitiveDataConstPtrs

Definition at line 20 of file Forward.h.

◆ PrimitiveDataPtr

using lanelet::PrimitiveDataPtr = typedef std::shared_ptr<PrimitiveData>

Definition at line 17 of file Forward.h.

◆ PrimitiveDataPtrs

using lanelet::PrimitiveDataPtrs = typedef std::vector<PrimitiveDataPtr>

Definition at line 19 of file Forward.h.

◆ RegulatoryElementConstPtr

using lanelet::RegulatoryElementConstPtr = typedef std::shared_ptr<const RegulatoryElement>

Definition at line 194 of file Forward.h.

◆ RegulatoryElementConstPtrs

Definition at line 195 of file Forward.h.

◆ RegulatoryElementDataConstPtr

using lanelet::RegulatoryElementDataConstPtr = typedef std::shared_ptr<const RegulatoryElementData>

Definition at line 185 of file Forward.h.

◆ RegulatoryElementDataConstPtrs

Definition at line 187 of file Forward.h.

◆ RegulatoryElementDataPtr

using lanelet::RegulatoryElementDataPtr = typedef std::shared_ptr<RegulatoryElementData>

Definition at line 184 of file Forward.h.

◆ RegulatoryElementDataPtrs

Definition at line 186 of file Forward.h.

◆ RegulatoryElementLayer

Definition at line 308 of file LaneletMap.h.

◆ RegulatoryElementPtr

using lanelet::RegulatoryElementPtr = typedef std::shared_ptr<RegulatoryElement>

Definition at line 192 of file Forward.h.

◆ RegulatoryElementPtrs

Definition at line 193 of file Forward.h.

◆ RuleParameter

We call every element of a rule a "parameter" A parameter can be any primitive in lanelet2

Definition at line 90 of file primitives/RegulatoryElement.h.

◆ RuleParameterMap

Rules are stored in a map internally.

Definition at line 127 of file primitives/RegulatoryElement.h.

◆ RuleParameters

using lanelet::RuleParameters = typedef std::vector<RuleParameter>

Multiple parameters can have the same role in a rule (eg traffic_lights)

Definition at line 121 of file primitives/RegulatoryElement.h.

◆ Segment

template<typename PointT >
using lanelet::Segment = typedef std::pair<PointT, PointT>

Definition at line 18 of file primitives/LineString.h.

◆ Segment2d

Definition at line 20 of file primitives/LineString.h.

◆ Segment3d

Definition at line 22 of file primitives/LineString.h.

◆ Velocity

Definition at line 210 of file Forward.h.

Enumeration Type Documentation

◆ AttributeName

Typical Attributes names within lanelet.

Enumerator
Type 
Subtype 
OneWay 
ParticipantVehicle 
ParticipantPedestrian 
SpeedLimit 
Location 
Dynamic 

Definition at line 185 of file Attribute.h.

◆ LaneletType

enum lanelet::LaneletType
strong
Enumerator
OneWay 
Bidirectional 

Definition at line 16 of file primitives/Lanelet.h.

◆ ManeuverType

enum lanelet::ManeuverType
strong

Enum to distinguish maneuver types.

Enumerator
Yield 
RightOfWay 

Lanelet has right of way

Lanelet has to yield

Unknown 

Lanelet ist not part of relation.

Definition at line 78 of file BasicRegulatoryElements.h.

◆ RoleName

enum lanelet::RoleName
strong

Typical role names within lanelet (for faster lookup)

Enumerator
Refers 

The primitive(s) that are the origin of this rule (ie signs)

RefLine 

The referring line where the rule becomes active.

RightOfWay 

A lanelet that has right of way in a relation.

Yield 

A lanelet that has to yield.

Cancels 

primitive(s) that invalidate a rule (eg end of speed zone)

CancelLine 

The line from which a rule is invalidated.

Definition at line 55 of file primitives/RegulatoryElement.h.

Function Documentation

◆ Attribute::as< Optional< std::string > >()

template<>
Optional<std::string> lanelet::Attribute::as< Optional< std::string > > ( ) const
inline

Definition at line 165 of file Attribute.h.

◆ Attribute::as< std::string >()

template<>
Optional<std::string> lanelet::Attribute::as< std::string > ( ) const
inline

Definition at line 160 of file Attribute.h.

◆ operator!=() [1/15]

bool lanelet::operator!= ( const Attribute lhs,
const Attribute rhs 
)
inline

Definition at line 180 of file Attribute.h.

◆ operator!=() [2/15]

template<typename Point1T , typename Point2T >
bool lanelet::operator!= ( const CompoundLineStringImpl< Point1T > &  lhs,
const CompoundLineStringImpl< Point2T > &  rhs 
)

Definition at line 366 of file CompoundLineString.h.

◆ operator!=() [3/15]

template<typename Point1T , typename Point2T >
bool lanelet::operator!= ( const CompoundLineStringImpl< Point1T > &  lhs,
const std::vector< Point2T > &  rhs 
)

Definition at line 380 of file CompoundLineString.h.

◆ operator!=() [4/15]

bool lanelet::operator!= ( const ConstArea lhs,
const ConstArea rhs 
)
inline

Definition at line 328 of file primitives/Area.h.

◆ operator!=() [5/15]

bool lanelet::operator!= ( const ConstLanelet lhs,
const ConstLanelet rhs 
)
inline

Definition at line 372 of file primitives/Lanelet.h.

◆ operator!=() [6/15]

bool lanelet::operator!= ( const ConstLaneletOrArea lhs,
const ConstLaneletOrArea rhs 
)
inline

Definition at line 102 of file LaneletOrArea.h.

◆ operator!=() [7/15]

template<typename LhsPointT , typename RhsPointT >
bool lanelet::operator!= ( const ConstLineStringImpl< LhsPointT > &  lhs,
const ConstLineStringImpl< RhsPointT > &  rhs 
)

Definition at line 718 of file primitives/LineString.h.

◆ operator!=() [8/15]

template<typename PointT >
bool lanelet::operator!= ( const ConstLineStringImpl< PointT > &  lhs,
const std::vector< PointT > &  rhs 
)

Definition at line 733 of file primitives/LineString.h.

◆ operator!=() [9/15]

bool lanelet::operator!= ( const ConstLineStringOrPolygon3d lhs,
const ConstLineStringOrPolygon3d rhs 
)
inline

Definition at line 128 of file LineStringOrPolygon.h.

◆ operator!=() [10/15]

bool lanelet::operator!= ( const ConstWeakArea lhs,
const ConstWeakArea rhs 
)
inline

Definition at line 332 of file primitives/Area.h.

◆ operator!=() [11/15]

bool lanelet::operator!= ( const ConstWeakLanelet lhs,
const ConstWeakLanelet rhs 
)
inline

Definition at line 376 of file primitives/Lanelet.h.

◆ operator!=() [12/15]

bool lanelet::operator!= ( const LaneletSequence lhs,
const LaneletSequence rhs 
)
inline

Definition at line 262 of file LaneletSequence.h.

◆ operator!=() [13/15]

bool lanelet::operator!= ( const LineStringOrPolygon3d lhs,
const LineStringOrPolygon3d rhs 
)
inline

Definition at line 123 of file LineStringOrPolygon.h.

◆ operator!=() [14/15]

template<typename Point1T , typename Point2T >
bool lanelet::operator!= ( const std::vector< Point1T > &  lhs,
const CompoundLineStringImpl< Point2T > &  rhs 
)

Definition at line 385 of file CompoundLineString.h.

◆ operator!=() [15/15]

template<typename PointT >
bool lanelet::operator!= ( const std::vector< PointT > &  lhs,
const ConstLineStringImpl< PointT > &  rhs 
)

Definition at line 738 of file primitives/LineString.h.

◆ operator<<() [1/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const Attribute obj 
)
inline

Definition at line 369 of file Attribute.h.

◆ operator<<() [2/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const AttributeMap obj 
)
inline

Definition at line 373 of file Attribute.h.

◆ operator<<() [3/19]

template<typename PointT >
std::ostream& lanelet::operator<< ( std::ostream &  stream,
const CompoundLineStringImpl< PointT > &  obj 
)
inline

Definition at line 390 of file CompoundLineString.h.

◆ operator<<() [4/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstArea obj 
)
inline

Definition at line 333 of file primitives/Area.h.

◆ operator<<() [5/19]

std::ostream & lanelet::operator<< ( std::ostream &  stream,
const ConstLanelet obj 
)

Definition at line 290 of file Lanelet.cpp.

◆ operator<<() [6/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstLaneletOrArea obj 
)
inline

Definition at line 104 of file LaneletOrArea.h.

◆ operator<<() [7/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstLineString2d obj 
)
inline

Definition at line 682 of file primitives/LineString.h.

◆ operator<<() [8/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstLineString3d obj 
)
inline

Definition at line 697 of file primitives/LineString.h.

◆ operator<<() [9/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstLineStringOrPolygon3d obj 
)
inline

Definition at line 139 of file LineStringOrPolygon.h.

◆ operator<<() [10/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstPoint2d obj 
)
inline

Definition at line 312 of file primitives/Point.h.

◆ operator<<() [11/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstPoint3d obj 
)
inline

Definition at line 316 of file primitives/Point.h.

◆ operator<<() [12/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstPolygon2d obj 
)
inline

Definition at line 332 of file primitives/Polygon.h.

◆ operator<<() [13/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const ConstPolygon3d obj 
)
inline

Definition at line 336 of file primitives/Polygon.h.

◆ operator<<() [14/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const LaneletSequence obj 
)
inline

Definition at line 264 of file LaneletSequence.h.

◆ operator<<() [15/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const LineStringOrPolygon3d obj 
)
inline

Definition at line 135 of file LineStringOrPolygon.h.

◆ operator<<() [16/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const Point2d obj 
)
inline

Definition at line 320 of file primitives/Point.h.

◆ operator<<() [17/19]

std::ostream& lanelet::operator<< ( std::ostream &  stream,
const Point3d obj 
)
inline

Definition at line 324 of file primitives/Point.h.

◆ operator<<() [18/19]

std::ostream & lanelet::operator<< ( std::ostream &  stream,
const RegulatoryElement obj 
)

Definition at line 175 of file RegulatoryElement.cpp.

◆ operator<<() [19/19]

template<typename Value , typename Enum , const std::pair< const char *, const Enum > Lookup>
std::ostream& lanelet::operator<< ( std::ostream &  stream,
HybridMap< Value, Enum, Lookup >  map 
)

Definition at line 235 of file HybridMap.h.

◆ operator==() [1/15]

bool lanelet::operator== ( const Attribute lhs,
const Attribute rhs 
)
inline

Definition at line 179 of file Attribute.h.

◆ operator==() [2/15]

template<typename Point1T , typename Point2T >
bool lanelet::operator== ( const CompoundLineStringImpl< Point1T > &  lhs,
const CompoundLineStringImpl< Point2T > &  rhs 
)

Definition at line 361 of file CompoundLineString.h.

◆ operator==() [3/15]

template<typename Point1T , typename Point2T >
bool lanelet::operator== ( const CompoundLineStringImpl< Point1T > &  lhs,
const std::vector< Point2T > &  rhs 
)

Definition at line 370 of file CompoundLineString.h.

◆ operator==() [4/15]

bool lanelet::operator== ( const ConstArea lhs,
const ConstArea rhs 
)
inline

Definition at line 327 of file primitives/Area.h.

◆ operator==() [5/15]

bool lanelet::operator== ( const ConstLanelet lhs,
const ConstLanelet rhs 
)
inline

Definition at line 369 of file primitives/Lanelet.h.

◆ operator==() [6/15]

bool lanelet::operator== ( const ConstLaneletOrArea lhs,
const ConstLaneletOrArea rhs 
)
inline

Definition at line 101 of file LaneletOrArea.h.

◆ operator==() [7/15]

template<typename LhsPointT , typename RhsPointT >
bool lanelet::operator== ( const ConstLineStringImpl< LhsPointT > &  lhs,
const ConstLineStringImpl< RhsPointT > &  rhs 
)

Definition at line 714 of file primitives/LineString.h.

◆ operator==() [8/15]

template<typename PointT >
bool lanelet::operator== ( const ConstLineStringImpl< PointT > &  lhs,
const std::vector< PointT > &  rhs 
)

Definition at line 723 of file primitives/LineString.h.

◆ operator==() [9/15]

bool lanelet::operator== ( const ConstLineStringOrPolygon3d lhs,
const ConstLineStringOrPolygon3d rhs 
)
inline

Definition at line 125 of file LineStringOrPolygon.h.

◆ operator==() [10/15]

bool lanelet::operator== ( const ConstWeakArea lhs,
const ConstWeakArea rhs 
)
inline

Definition at line 329 of file primitives/Area.h.

◆ operator==() [11/15]

bool lanelet::operator== ( const ConstWeakLanelet lhs,
const ConstWeakLanelet rhs 
)
inline

Definition at line 373 of file primitives/Lanelet.h.

◆ operator==() [12/15]

bool lanelet::operator== ( const LaneletSequence lhs,
const LaneletSequence rhs 
)
inline

Definition at line 259 of file LaneletSequence.h.

◆ operator==() [13/15]

bool lanelet::operator== ( const LineStringOrPolygon3d lhs,
const LineStringOrPolygon3d rhs 
)
inline

Definition at line 122 of file LineStringOrPolygon.h.

◆ operator==() [14/15]

template<typename Point1T , typename Point2T >
bool lanelet::operator== ( const std::vector< Point1T > &  lhs,
const CompoundLineStringImpl< Point2T > &  rhs 
)

Definition at line 375 of file CompoundLineString.h.

◆ operator==() [15/15]

template<typename PointT >
bool lanelet::operator== ( const std::vector< PointT > &  lhs,
const ConstLineStringImpl< PointT > &  rhs 
)

Definition at line 728 of file primitives/LineString.h.

Variable Documentation

◆ genRegelem

Definition at line 87 of file RegulatoryElement.cpp.

◆ InvalId

constexpr Id lanelet::InvalId = 0
constexpr

indicates a primitive that is not part of a map

Definition at line 199 of file Forward.h.

◆ regAllWayStop

RegisterRegulatoryElement<AllWayStop> lanelet::regAllWayStop
static

Definition at line 159 of file BasicRegulatoryElements.cpp.

◆ regRightOfWay

RegisterRegulatoryElement<RightOfWay> lanelet::regRightOfWay
static

Definition at line 156 of file BasicRegulatoryElements.cpp.

◆ regSpeedLimit

RegisterRegulatoryElement<SpeedLimit> lanelet::regSpeedLimit
static

Definition at line 158 of file BasicRegulatoryElements.cpp.

◆ regTraffic

RegisterRegulatoryElement<TrafficLight> lanelet::regTraffic
static

Definition at line 155 of file BasicRegulatoryElements.cpp.

◆ regTrafficSign

RegisterRegulatoryElement<TrafficSign> lanelet::regTrafficSign
static

Definition at line 157 of file BasicRegulatoryElements.cpp.



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