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 |
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< GenericRegulatoryElement > | genRegelem |
| constexpr Id | InvalId = 0 |
| indicates a primitive that is not part of a map More... | |
| static RegisterRegulatoryElement< AllWayStop > | regAllWayStop |
| static RegisterRegulatoryElement< RightOfWay > | regRightOfWay |
| static RegisterRegulatoryElement< SpeedLimit > | regSpeedLimit |
| static RegisterRegulatoryElement< TrafficLight > | regTraffic |
| static RegisterRegulatoryElement< TrafficSign > | regTrafficSign |
basic namespace for everything in lanelet2
| using lanelet::Acceleration = typedef units::MPS2Quantity |
| using lanelet::AreaDataConstPtr = typedef std::shared_ptr<const AreaData> |
| using lanelet::AreaDataConstPtrs = typedef std::vector<AreaDataConstPtr> |
| using lanelet::AreaDataPtr = typedef std::shared_ptr<AreaData> |
| using lanelet::AreaDataptr = typedef std::weak_ptr<AreaData> |
| using lanelet::AreaDataPtrs = typedef std::vector<AreaDataPtr> |
| using lanelet::Areas = typedef std::vector<Area> |
| using lanelet::AttributeMap = typedef HybridMap<Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map> |
Definition at line 371 of file Attribute.h.
| using lanelet::AttributeNamesItem = typedef std::pair<const char*, const AttributeName> |
Definition at line 196 of file Attribute.h.
| using lanelet::BasicLineString2d = typedef BasicPoints2d |
Definition at line 14 of file primitives/LineString.h.
| using lanelet::BasicLineString3d = typedef BasicPoints3d |
Definition at line 15 of file primitives/LineString.h.
| using lanelet::BasicPoint2d = typedef Eigen::Matrix<double, 2, 1, Eigen::DontAlign> |
a simple 2d-point
Definition at line 20 of file primitives/Point.h.
| using lanelet::BasicPoint3d = typedef Eigen::Vector3d |
a simple 3d-point
Definition at line 19 of file primitives/Point.h.
| 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.
| using lanelet::BasicPoints3d = typedef std::vector<BasicPoint3d> |
multiple simple 3d-points
Definition at line 23 of file primitives/Point.h.
| using lanelet::BasicPolygons2d = typedef std::vector<BasicPolygon2d> |
| using lanelet::BasicPolygons3d = typedef std::vector<BasicPolygon3d> |
| using lanelet::BasicPolygonsWithHoles2d = typedef std::vector<BasicPolygonWithHoles2d> |
| using lanelet::BasicPolygonsWithHoles3d = typedef std::vector<BasicPolygonWithHoles3d> |
| using lanelet::BasicSegment2d = typedef Segment<BasicPoint2d> |
Definition at line 24 of file primitives/LineString.h.
| using lanelet::BasicSegment3d = typedef Segment<BasicPoint3d> |
Definition at line 25 of file primitives/LineString.h.
| 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.
| using lanelet::CompoundHybridLineStrings2d = typedef std::vector<CompoundHybridLineString2d> |
| using lanelet::CompoundHybridLineStrings3d = typedef std::vector<CompoundHybridLineString3d> |
| using lanelet::CompoundHybridPolygons2d = typedef std::vector<CompoundHybridPolygon2d> |
| using lanelet::CompoundHybridPolygons3d = typedef std::vector<CompoundHybridPolygon3d> |
| using lanelet::CompoundLineStringDataConstPtr = typedef std::shared_ptr<const CompoundLineStringData> |
| using lanelet::CompoundLineStringDataConstPtrs = typedef std::vector<CompoundLineStringDataConstPtr> |
| using lanelet::CompoundLineStringDataPtr = typedef std::shared_ptr<CompoundLineStringData> |
| using lanelet::CompoundLineStringDataPtrs = typedef std::vector<CompoundLineStringDataPtr> |
| using lanelet::CompoundLineStrings2d = typedef std::vector<CompoundLineString2d> |
| using lanelet::CompoundLineStrings3d = typedef std::vector<CompoundLineString3d> |
| using lanelet::CompoundPolygons2d = typedef std::vector<CompoundPolygon2d> |
| using lanelet::CompoundPolygons3d = typedef std::vector<CompoundPolygon3d> |
| using lanelet::ConstAreas = typedef std::vector<ConstArea> |
| using lanelet::ConstHybridLineStrings2d = typedef std::vector<ConstHybridLineString2d> |
| using lanelet::ConstHybridLineStrings3d = typedef std::vector<ConstHybridLineString3d> |
| using lanelet::ConstHybridPolygons2d = typedef std::vector<ConstHybridPolygon2d> |
| using lanelet::ConstHybridPolygons3d = typedef std::vector<ConstHybridPolygon3d> |
| using lanelet::ConstInnerBounds = typedef std::vector<ConstLineStrings3d> |
Definition at line 39 of file primitives/Area.h.
| using lanelet::ConstLaneletOrAreas = typedef std::vector<ConstLaneletOrArea> |
| using lanelet::ConstLanelets = typedef std::vector<ConstLanelet> |
| using lanelet::ConstLineStrings2d = typedef std::vector<ConstLineString2d> |
| using lanelet::ConstLineStrings3d = typedef std::vector<ConstLineString3d> |
| using lanelet::ConstLineStringsOrPolygons3d = typedef std::vector<ConstLineStringOrPolygon3d> |
Definition at line 133 of file LineStringOrPolygon.h.
| using lanelet::ConstPoints2d = typedef std::vector<ConstPoint2d> |
| using lanelet::ConstPoints3d = typedef std::vector<ConstPoint3d> |
| using lanelet::ConstPolygons2d = typedef std::vector<ConstPolygon2d> |
| using lanelet::ConstPolygons3d = typedef std::vector<ConstPolygon3d> |
| using lanelet::ConstRuleParameter = typedef boost::variant<ConstPoint3d, ConstLineString3d, ConstPolygon3d, ConstWeakLanelet, ConstWeakArea> |
Const-version of the parameters.
Definition at line 94 of file primitives/RegulatoryElement.h.
| using lanelet::ConstRuleParameterMap = typedef HybridMap<ConstRuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map> |
Rules are stored in a map internally (const version)
Definition at line 130 of file primitives/RegulatoryElement.h.
| using lanelet::ConstRuleParameters = typedef std::vector<ConstRuleParameter> |
Const version for a range of rule parameters.
Definition at line 124 of file primitives/RegulatoryElement.h.
| using lanelet::ConstSegment2d = typedef Segment<ConstPoint2d> |
Definition at line 21 of file primitives/LineString.h.
| using lanelet::ConstSegment3d = typedef Segment<ConstPoint3d> |
Definition at line 23 of file primitives/LineString.h.
| using lanelet::GPSPoints = typedef std::vector<GPSPoint> |
| using lanelet::Id = typedef int64_t |
| using lanelet::Ids = typedef std::vector<Id> |
| using lanelet::IfAr = typedef std::enable_if_t<traits::isAreaT<T>(), RetT> |
Definition at line 364 of file primitives/Area.h.
| using lanelet::IfLL = typedef std::enable_if_t<traits::isLaneletT<T>(), RetT> |
Definition at line 387 of file primitives/Lanelet.h.
| using lanelet::IfLS = typedef std::enable_if_t<traits::isLinestringT<T>(), RetT> |
Definition at line 771 of file primitives/LineString.h.
| using lanelet::IfLS2 = typedef std::enable_if_t<traits::isLinestringT<T1>() && traits::isLinestringT<T2>(), RetT> |
Definition at line 774 of file primitives/LineString.h.
| using lanelet::IfPoly = typedef std::enable_if_t<traits::isPolygonT<T>(), RetT> |
Definition at line 428 of file primitives/Polygon.h.
| using lanelet::IfPT = typedef std::enable_if_t<traits::isPointT<T>(), RetT> |
Definition at line 335 of file primitives/Point.h.
| using lanelet::IfRE = typedef std::enable_if_t<traits::isRegulatoryElementT<T>(), RetT> |
Definition at line 508 of file primitives/RegulatoryElement.h.
| using lanelet::InnerBounds = typedef std::vector<LineStrings3d> |
Definition at line 38 of file primitives/Area.h.
| using lanelet::LaneletDataConstPtr = typedef std::shared_ptr<const LaneletData> |
| using lanelet::LaneletDataConstPtrs = typedef std::vector<LaneletDataConstPtr> |
| using lanelet::LaneletDataConstWptr = typedef std::weak_ptr<const LaneletData> |
| using lanelet::LaneletDataConstWptrs = typedef std::vector<LaneletDataConstWptr> |
| using lanelet::LaneletDataPtr = typedef std::shared_ptr<LaneletData> |
| using lanelet::LaneletDataptr = typedef std::weak_ptr<LaneletData> |
| using lanelet::LaneletDataPtrs = typedef std::vector<LaneletDataPtr> |
| using lanelet::LaneletMapConstPtr = typedef std::shared_ptr<const LaneletMap> |
| using lanelet::LaneletMapConstPtrs = typedef std::vector<LaneletMapConstPtr> |
| using lanelet::LaneletMapConstUPtr = typedef std::unique_ptr<const LaneletMap> |
| using lanelet::LaneletMapPtr = typedef std::shared_ptr<LaneletMap> |
| using lanelet::LaneletMapPtrs = typedef std::vector<LaneletMapPtr> |
| using lanelet::LaneletMapUPtr = typedef std::unique_ptr<LaneletMap> |
| using lanelet::Lanelets = typedef std::vector<Lanelet> |
| using lanelet::LaneletSequenceDataConstPtr = typedef std::shared_ptr<const LaneletSequenceData> |
| using lanelet::LaneletSequenceDataConstPtrs = typedef std::vector<LaneletSequenceDataConstPtr> |
| using lanelet::LaneletSequenceDataPtr = typedef std::shared_ptr<LaneletSequenceData> |
| using lanelet::LaneletSequenceDataPtrs = typedef std::vector<LaneletSequenceDataPtr> |
| using lanelet::LaneletSequences = typedef std::vector<LaneletSequence> |
| using lanelet::LaneletSubmapConstPtr = typedef std::shared_ptr<const LaneletSubmap> |
| using lanelet::LaneletSubmapConstPtrs = typedef std::vector<LaneletSubmapConstPtr> |
| using lanelet::LaneletSubmapConstUPtr = typedef std::unique_ptr<const LaneletSubmap> |
| using lanelet::LaneletSubmapPtr = typedef std::shared_ptr<LaneletSubmap> |
| using lanelet::LaneletSubmapPtrs = typedef std::vector<LaneletSubmapPtr> |
| using lanelet::LaneletSubmapUPtr = typedef std::unique_ptr<LaneletSubmap> |
| using lanelet::LaneletsWithStopLines = typedef std::vector<LaneletWithStopLine> |
Definition at line 154 of file BasicRegulatoryElements.h.
| using lanelet::LineStringDataConstPtr = typedef std::shared_ptr<const LineStringData> |
| using lanelet::LineStringDataConstPtrs = typedef std::vector<LineStringDataConstPtr> |
| using lanelet::LineStringDataPtr = typedef std::shared_ptr<LineStringData> |
| using lanelet::LineStringDataPtrs = typedef std::vector<LineStringDataPtr> |
| using lanelet::LineStringLayer = typedef PrimitiveLayer<LineString3d> |
Definition at line 306 of file LaneletMap.h.
| using lanelet::LineStrings2d = typedef std::vector<LineString2d> |
| using lanelet::LineStrings3d = typedef std::vector<LineString3d> |
| using lanelet::LineStringsOrPolygons3d = typedef std::vector<LineStringOrPolygon3d> |
Definition at line 132 of file LineStringOrPolygon.h.
| using lanelet::OptDistance = typedef boost::optional<double> |
Definition at line 14 of file Lanelet.cpp.
| using lanelet::Optional = typedef boost::optional<T> |
Definition at line 7 of file Optional.h.
| using lanelet::PointDataConstPtr = typedef std::shared_ptr<const PointData> |
| using lanelet::PointDataConstPtrs = typedef std::vector<PointDataConstPtr> |
| using lanelet::PointDataPtr = typedef std::shared_ptr<PointData> |
| using lanelet::PointDataPtrs = typedef std::vector<PointDataPtr> |
| using lanelet::PointLayer = typedef PrimitiveLayer<Point3d> |
Definition at line 307 of file LaneletMap.h.
| using lanelet::Points2d = typedef std::vector<Point2d> |
| using lanelet::Points3d = typedef std::vector<Point3d> |
| using lanelet::PolygonLayer = typedef PrimitiveLayer<Polygon3d> |
Definition at line 305 of file LaneletMap.h.
| using lanelet::Polygons2d = typedef std::vector<Polygon2d> |
| using lanelet::Polygons3d = typedef std::vector<Polygon3d> |
| using lanelet::PrimitiveDataConstPtr = typedef std::shared_ptr<const PrimitiveData> |
| using lanelet::PrimitiveDataConstPtrs = typedef std::vector<PrimitiveDataConstPtr> |
| using lanelet::PrimitiveDataPtr = typedef std::shared_ptr<PrimitiveData> |
| using lanelet::PrimitiveDataPtrs = typedef std::vector<PrimitiveDataPtr> |
| using lanelet::RegulatoryElementConstPtr = typedef std::shared_ptr<const RegulatoryElement> |
| using lanelet::RegulatoryElementConstPtrs = typedef std::vector<RegulatoryElementConstPtr> |
| using lanelet::RegulatoryElementDataConstPtr = typedef std::shared_ptr<const RegulatoryElementData> |
| using lanelet::RegulatoryElementDataConstPtrs = typedef std::vector<RegulatoryElementDataConstPtr> |
| using lanelet::RegulatoryElementDataPtr = typedef std::shared_ptr<RegulatoryElementData> |
| using lanelet::RegulatoryElementDataPtrs = typedef std::vector<RegulatoryElementDataPtr> |
| using lanelet::RegulatoryElementLayer = typedef PrimitiveLayer<RegulatoryElementPtr> |
Definition at line 308 of file LaneletMap.h.
| using lanelet::RegulatoryElementPtr = typedef std::shared_ptr<RegulatoryElement> |
| using lanelet::RegulatoryElementPtrs = typedef std::vector<RegulatoryElementPtr> |
| using lanelet::RuleParameter = typedef boost::variant<Point3d, LineString3d, Polygon3d, WeakLanelet, WeakArea> |
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.
| using lanelet::RuleParameterMap = typedef HybridMap<RuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map> |
Rules are stored in a map internally.
Definition at line 127 of file primitives/RegulatoryElement.h.
| 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.
| using lanelet::Segment = typedef std::pair<PointT, PointT> |
Definition at line 18 of file primitives/LineString.h.
| using lanelet::Segment2d = typedef Segment<Point2d> |
Definition at line 20 of file primitives/LineString.h.
| using lanelet::Segment3d = typedef Segment<Point3d> |
Definition at line 22 of file primitives/LineString.h.
| using lanelet::Velocity = typedef units::MPSQuantity |
|
strong |
Typical Attributes names within lanelet.
| Enumerator | |
|---|---|
| Type | |
| Subtype | |
| OneWay | |
| ParticipantVehicle | |
| ParticipantPedestrian | |
| SpeedLimit | |
| Location | |
| Dynamic | |
Definition at line 185 of file Attribute.h.
|
strong |
| Enumerator | |
|---|---|
| OneWay | |
| Bidirectional | |
Definition at line 16 of file primitives/Lanelet.h.
|
strong |
Enum to distinguish maneuver types.
| Enumerator | |
|---|---|
| Yield | |
| RightOfWay |
Lanelet has to yield |
| Unknown | Lanelet ist not part of relation. |
Definition at line 78 of file BasicRegulatoryElements.h.
|
strong |
Typical role names within lanelet (for faster lookup)
Definition at line 55 of file primitives/RegulatoryElement.h.
|
inline |
Definition at line 165 of file Attribute.h.
|
inline |
Definition at line 160 of file Attribute.h.
Definition at line 180 of file Attribute.h.
| bool lanelet::operator!= | ( | const CompoundLineStringImpl< Point1T > & | lhs, |
| const CompoundLineStringImpl< Point2T > & | rhs | ||
| ) |
Definition at line 366 of file CompoundLineString.h.
| bool lanelet::operator!= | ( | const CompoundLineStringImpl< Point1T > & | lhs, |
| const std::vector< Point2T > & | rhs | ||
| ) |
Definition at line 380 of file CompoundLineString.h.
Definition at line 328 of file primitives/Area.h.
|
inline |
Definition at line 372 of file primitives/Lanelet.h.
|
inline |
Definition at line 102 of file LaneletOrArea.h.
| bool lanelet::operator!= | ( | const ConstLineStringImpl< LhsPointT > & | lhs, |
| const ConstLineStringImpl< RhsPointT > & | rhs | ||
| ) |
Definition at line 718 of file primitives/LineString.h.
| bool lanelet::operator!= | ( | const ConstLineStringImpl< PointT > & | lhs, |
| const std::vector< PointT > & | rhs | ||
| ) |
Definition at line 733 of file primitives/LineString.h.
|
inline |
Definition at line 128 of file LineStringOrPolygon.h.
|
inline |
Definition at line 332 of file primitives/Area.h.
|
inline |
Definition at line 376 of file primitives/Lanelet.h.
|
inline |
Definition at line 262 of file LaneletSequence.h.
|
inline |
Definition at line 123 of file LineStringOrPolygon.h.
| bool lanelet::operator!= | ( | const std::vector< Point1T > & | lhs, |
| const CompoundLineStringImpl< Point2T > & | rhs | ||
| ) |
Definition at line 385 of file CompoundLineString.h.
| bool lanelet::operator!= | ( | const std::vector< PointT > & | lhs, |
| const ConstLineStringImpl< PointT > & | rhs | ||
| ) |
Definition at line 738 of file primitives/LineString.h.
|
inline |
Definition at line 369 of file Attribute.h.
|
inline |
Definition at line 373 of file Attribute.h.
|
inline |
Definition at line 390 of file CompoundLineString.h.
|
inline |
Definition at line 333 of file primitives/Area.h.
| std::ostream & lanelet::operator<< | ( | std::ostream & | stream, |
| const ConstLanelet & | obj | ||
| ) |
Definition at line 290 of file Lanelet.cpp.
|
inline |
Definition at line 104 of file LaneletOrArea.h.
|
inline |
Definition at line 682 of file primitives/LineString.h.
|
inline |
Definition at line 697 of file primitives/LineString.h.
|
inline |
Definition at line 139 of file LineStringOrPolygon.h.
|
inline |
Definition at line 312 of file primitives/Point.h.
|
inline |
Definition at line 316 of file primitives/Point.h.
|
inline |
Definition at line 332 of file primitives/Polygon.h.
|
inline |
Definition at line 336 of file primitives/Polygon.h.
|
inline |
Definition at line 264 of file LaneletSequence.h.
|
inline |
Definition at line 135 of file LineStringOrPolygon.h.
|
inline |
Definition at line 320 of file primitives/Point.h.
|
inline |
Definition at line 324 of file primitives/Point.h.
| std::ostream & lanelet::operator<< | ( | std::ostream & | stream, |
| const RegulatoryElement & | obj | ||
| ) |
Definition at line 175 of file RegulatoryElement.cpp.
| std::ostream& lanelet::operator<< | ( | std::ostream & | stream, |
| HybridMap< Value, Enum, Lookup > | map | ||
| ) |
Definition at line 235 of file HybridMap.h.
Definition at line 179 of file Attribute.h.
| bool lanelet::operator== | ( | const CompoundLineStringImpl< Point1T > & | lhs, |
| const CompoundLineStringImpl< Point2T > & | rhs | ||
| ) |
Definition at line 361 of file CompoundLineString.h.
| bool lanelet::operator== | ( | const CompoundLineStringImpl< Point1T > & | lhs, |
| const std::vector< Point2T > & | rhs | ||
| ) |
Definition at line 370 of file CompoundLineString.h.
Definition at line 327 of file primitives/Area.h.
|
inline |
Definition at line 369 of file primitives/Lanelet.h.
|
inline |
Definition at line 101 of file LaneletOrArea.h.
| bool lanelet::operator== | ( | const ConstLineStringImpl< LhsPointT > & | lhs, |
| const ConstLineStringImpl< RhsPointT > & | rhs | ||
| ) |
Definition at line 714 of file primitives/LineString.h.
| bool lanelet::operator== | ( | const ConstLineStringImpl< PointT > & | lhs, |
| const std::vector< PointT > & | rhs | ||
| ) |
Definition at line 723 of file primitives/LineString.h.
|
inline |
Definition at line 125 of file LineStringOrPolygon.h.
|
inline |
Definition at line 329 of file primitives/Area.h.
|
inline |
Definition at line 373 of file primitives/Lanelet.h.
|
inline |
Definition at line 259 of file LaneletSequence.h.
|
inline |
Definition at line 122 of file LineStringOrPolygon.h.
| bool lanelet::operator== | ( | const std::vector< Point1T > & | lhs, |
| const CompoundLineStringImpl< Point2T > & | rhs | ||
| ) |
Definition at line 375 of file CompoundLineString.h.
| bool lanelet::operator== | ( | const std::vector< PointT > & | lhs, |
| const ConstLineStringImpl< PointT > & | rhs | ||
| ) |
Definition at line 728 of file primitives/LineString.h.
|
static |
Definition at line 87 of file RegulatoryElement.cpp.
|
constexpr |
|
static |
Definition at line 159 of file BasicRegulatoryElements.cpp.
|
static |
Definition at line 156 of file BasicRegulatoryElements.cpp.
|
static |
Definition at line 158 of file BasicRegulatoryElements.cpp.
|
static |
Definition at line 155 of file BasicRegulatoryElements.cpp.
|
static |
Definition at line 157 of file BasicRegulatoryElements.cpp.