Class LaneletSequence
Defined in File LaneletSequence.h
Class Documentation
-
class LaneletSequence
A collection of Lanelets.
A LaneletSequence is a collection of Lanelets that behaves like like one single Lanelet. Because of that, it can be passed to most functions expecting a normal lanelet.
See also
The contents of a LaneletSequence can not be modified. Modifications have to be done to the Lanelets directly.
If
Public Types
-
using DataType = LaneletSequenceData
-
using TwoDType = void
-
using ThreeDType = void
-
using HybridType = void
-
using ConstType = LaneletSequence
-
using MutableType = void
-
using iterator = LaneletSequenceData::iterator
Public Functions
-
inline LaneletSequence(ConstLanelets ls = ConstLanelets())
Construct from a vector of ConstLineString3d.
- Parameters:
ls – objects to construct from. The order will also be the order of the linestrings.
-
inline explicit LaneletSequence(const LaneletSequences &ls)
Create a compound lanelet from other compound lanelets.
- Parameters:
ls – vector of compound lanelets
-
inline LaneletSequence(LaneletSequenceDataConstPtr data, bool inverted)
-
inline bool inverted() const
returns out if this is an inverted lanelets.
Inverted LaneletSequences behave differently from normal lanelets in that they internally interpret their inverted left bound as right bound and vice versa.
- Returns:
true if inverted
-
inline bool empty() const noexcept
Returns wether this holds any lanelets.
-
inline size_t size() const noexcept
Returns number of lanelets.
-
inline LaneletSequence invert() const
returns the respective inverted LaneletSequence
Both lanelets (this and the inverted one) share the same data. Inversion only requires copying a shared ptr.
-
inline CompoundLineString3d leftBound() const
get the combined left bounds of all lanelets
-
inline CompoundLineString2d leftBound2d() const
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
-
inline CompoundLineString3d leftBound3d() const
-
inline CompoundLineString3d rightBound() const
get the combined right bounds of all lanelets
-
inline CompoundLineString2d rightBound2d() const
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
-
inline CompoundLineString3d rightBound3d() const
get the combined right bounds of all lanelets
-
RegulatoryElementConstPtrs regulatoryElements() const
get a list of all regulatory elements that affect one of the lanelets
get all regulatory elements of type RegElemT
- Returns:
list of pointers to regulatory elements in the LaneletSequence
-
inline CompoundLineString3d centerline() const
get the centerline of this lanelet
Note the computation of the centerline is expensive, but as the result is cached, repeated calls to this functions are cheap.
The returned centerline is only guarateed to be within the the lanelet, but not always perfecly in the middle of it. However, if your lanelet is more or less monotonic, this is negligible.
The start (and similarly the end point) will always be direcly in the middle between the first left and right points.
-
inline CompoundLineString3d centerline3d() const
-
inline CompoundLineString2d centerline2d() const
-
inline CompoundPolygon3d polygon3d() const
returns the surface covered by the lanelets as 3-dimensional polygon. The result of the computation is cached, therefore foo(polygon().begin(), polygon.end()) provides valid iterators.
Note that many geometry functions are only available for a 2d-polygon.
-
inline CompoundPolygon2d polygon2d() const
returns the surface covered by the lanelets as 2-dimensional polygon.
-
inline ConstLanelets lanelets() const
returns the lanelets that are part of this object
- Returns:
vector of lanelets
-
inline iterator begin() const noexcept
Returns iterator to the first lanelet (or to the last, if inverted)
-
inline iterator end() const noexcept
Returns iterator to the last lanelet (or to the first, if inverted)
-
inline const ConstLanelet &operator[](size_t idx) const
Access an individual lanelet.
-
inline LaneletSequenceDataConstPtr constData() const
returns the internal data on the linestrings managed by this object
-
inline void resetCache()
call this function if one of the contained Lanelets was modified to give this object the opportunity to update its cache.
-
using DataType = LaneletSequenceData