Public Types | Public Member Functions | Private Attributes | List of all members
lanelet::LaneletSequence Class Reference

A collection of Lanelets. More...

#include <LaneletSequence.h>

Public Types

using ConstType = LaneletSequence
 
using DataType = LaneletSequenceData
 
using HybridType = void
 
using iterator = LaneletSequenceData::iterator
 
using MutableType = void
 
using ThreeDType = void
 
using TwoDType = void
 

Public Member Functions

iterator begin () const noexcept
 Returns iterator to the first lanelet (or to the last, if inverted) More...
 
CompoundLineString3d centerline () const
 get the centerline of this lanelet More...
 
CompoundLineString2d centerline2d () const
 
CompoundLineString3d centerline3d () const
 
LaneletSequenceDataConstPtr constData () const
 returns the internal data on the linestrings managed by this object More...
 
bool empty () const noexcept
 Returns wether this holds any lanelets. More...
 
iterator end () const noexcept
 Returns iterator to the last lanelet (or to the first, if inverted) More...
 
Ids ids () const
 returns the ids of all lanelets in order More...
 
LaneletSequence invert () const
 returns the respective inverted LaneletSequence More...
 
bool inverted () const
 returns out if this is an inverted lanelets. More...
 
ConstLanelets lanelets () const
 returns the lanelets that are part of this object More...
 
 LaneletSequence (const LaneletSequences &ls)
 Create a compound lanelet from other compound lanelets. More...
 
 LaneletSequence (ConstLanelets ls=ConstLanelets())
 Construct from a vector of ConstLineString3d. More...
 
 LaneletSequence (LaneletSequenceDataConstPtr data, bool inverted)
 
CompoundLineString3d leftBound () const
 get the combined left bounds of all lanelets More...
 
CompoundLineString2d leftBound2d () const
 get the left bound in 2d. To be used over leftBound where geometric calculations are required. More...
 
CompoundLineString3d leftBound3d () const
 
const ConstLaneletoperator[] (size_t idx) const
 Access an individual lanelet. More...
 
CompoundPolygon2d polygon2d () const
 returns the surface covered by the lanelets as 2-dimensional polygon. More...
 
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. More...
 
RegulatoryElementConstPtrs regulatoryElements () const
 get a list of all regulatory elements that affect one of the lanelets More...
 
template<typename RegElemT >
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs () const
 get all regulatory elements of type RegElemT More...
 
void resetCache ()
 call this function if one of the contained Lanelets was modified to give this object the opportunity to update its cache. More...
 
CompoundLineString3d rightBound () const
 get the combined right bounds of all lanelets More...
 
CompoundLineString2d rightBound2d () const
 get the right bound in 2d. To be used over rightBound where geometric calculations are required. More...
 
CompoundLineString3d rightBound3d () const
 get the combined right bounds of all lanelets More...
 
size_t size () const noexcept
 Returns number of lanelets. More...
 

Private Attributes

std::shared_ptr< const LaneletSequenceDatadata_
 internal data More...
 
bool inverted_ {false}
 Flag that indicates this lanelet is inverted. More...
 

Detailed Description

A collection of Lanelets.

See also
ConstLanelet

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.

The contents of a LaneletSequence can not be modified. Modifications have to be done to the Lanelets directly.

If

Definition at line 85 of file LaneletSequence.h.

Member Typedef Documentation

◆ ConstType

Definition at line 91 of file LaneletSequence.h.

◆ DataType

Definition at line 87 of file LaneletSequence.h.

◆ HybridType

Definition at line 90 of file LaneletSequence.h.

◆ iterator

Definition at line 93 of file LaneletSequence.h.

◆ MutableType

Definition at line 92 of file LaneletSequence.h.

◆ ThreeDType

Definition at line 89 of file LaneletSequence.h.

◆ TwoDType

Definition at line 88 of file LaneletSequence.h.

Constructor & Destructor Documentation

◆ LaneletSequence() [1/3]

lanelet::LaneletSequence::LaneletSequence ( ConstLanelets  ls = ConstLanelets())
inline

Construct from a vector of ConstLineString3d.

Parameters
lsobjects to construct from. The order will also be the order of the linestrings.

Definition at line 100 of file LaneletSequence.h.

◆ LaneletSequence() [2/3]

lanelet::LaneletSequence::LaneletSequence ( const LaneletSequences ls)
inlineexplicit

Create a compound lanelet from other compound lanelets.

Parameters
lsvector of compound lanelets

Definition at line 107 of file LaneletSequence.h.

◆ LaneletSequence() [3/3]

lanelet::LaneletSequence::LaneletSequence ( LaneletSequenceDataConstPtr  data,
bool  inverted 
)
inline

Definition at line 110 of file LaneletSequence.h.

Member Function Documentation

◆ begin()

iterator lanelet::LaneletSequence::begin ( ) const
inlinenoexcept

Returns iterator to the first lanelet (or to the last, if inverted)

Definition at line 209 of file LaneletSequence.h.

◆ centerline()

CompoundLineString3d lanelet::LaneletSequence::centerline ( ) const
inline

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.

Definition at line 180 of file LaneletSequence.h.

◆ centerline2d()

CompoundLineString2d lanelet::LaneletSequence::centerline2d ( ) const
inline

Definition at line 184 of file LaneletSequence.h.

◆ centerline3d()

CompoundLineString3d lanelet::LaneletSequence::centerline3d ( ) const
inline

Definition at line 181 of file LaneletSequence.h.

◆ constData()

LaneletSequenceDataConstPtr lanelet::LaneletSequence::constData ( ) const
inline

returns the internal data on the linestrings managed by this object

Definition at line 231 of file LaneletSequence.h.

◆ empty()

bool lanelet::LaneletSequence::empty ( ) const
inlinenoexcept

Returns wether this holds any lanelets.

Definition at line 123 of file LaneletSequence.h.

◆ end()

iterator lanelet::LaneletSequence::end ( ) const
inlinenoexcept

Returns iterator to the last lanelet (or to the first, if inverted)

Definition at line 212 of file LaneletSequence.h.

◆ ids()

Ids lanelet::LaneletSequence::ids ( ) const
inline

returns the ids of all lanelets in order

Returns
list of ids

Definition at line 224 of file LaneletSequence.h.

◆ invert()

LaneletSequence lanelet::LaneletSequence::invert ( ) const
inline

returns the respective inverted LaneletSequence

Both lanelets (this and the inverted one) share the same data. Inversion only requires copying a shared ptr.

Definition at line 134 of file LaneletSequence.h.

◆ inverted()

bool lanelet::LaneletSequence::inverted ( ) const
inline

returns out if this is an inverted lanelets.

Returns
true if inverted

Inverted LaneletSequences behave differently from normal lanelets in that they internally interpret their inverted left bound as right bound and vice versa.

Definition at line 120 of file LaneletSequence.h.

◆ lanelets()

ConstLanelets lanelet::LaneletSequence::lanelets ( ) const
inline

returns the lanelets that are part of this object

Returns
vector of lanelets

Definition at line 206 of file LaneletSequence.h.

◆ leftBound()

CompoundLineString3d lanelet::LaneletSequence::leftBound ( ) const
inline

get the combined left bounds of all lanelets

Definition at line 137 of file LaneletSequence.h.

◆ leftBound2d()

CompoundLineString2d lanelet::LaneletSequence::leftBound2d ( ) const
inline

get the left bound in 2d. To be used over leftBound where geometric calculations are required.

Definition at line 139 of file LaneletSequence.h.

◆ leftBound3d()

CompoundLineString3d lanelet::LaneletSequence::leftBound3d ( ) const
inline

Definition at line 140 of file LaneletSequence.h.

◆ operator[]()

const ConstLanelet& lanelet::LaneletSequence::operator[] ( size_t  idx) const
inline

Access an individual lanelet.

Definition at line 215 of file LaneletSequence.h.

◆ polygon2d()

CompoundPolygon2d lanelet::LaneletSequence::polygon2d ( ) const
inline

returns the surface covered by the lanelets as 2-dimensional polygon.

Definition at line 200 of file LaneletSequence.h.

◆ polygon3d()

CompoundPolygon3d lanelet::LaneletSequence::polygon3d ( ) const
inline

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.

Definition at line 194 of file LaneletSequence.h.

◆ regulatoryElements()

RegulatoryElementConstPtrs lanelet::LaneletSequence::regulatoryElements ( ) const

get a list of all regulatory elements that affect one of the lanelets

Definition at line 29 of file LaneletSequence.cpp.

◆ regulatoryElementsAs()

template<typename RegElemT >
std::vector<std::shared_ptr<const RegElemT> > lanelet::LaneletSequence::regulatoryElementsAs ( ) const
inline

get all regulatory elements of type RegElemT

Returns
list of pointers to regulatory elements in the LaneletSequence

Definition at line 161 of file LaneletSequence.h.

◆ resetCache()

void lanelet::LaneletSequence::resetCache ( )
inline

call this function if one of the contained Lanelets was modified to give this object the opportunity to update its cache.

Definition at line 238 of file LaneletSequence.h.

◆ rightBound()

CompoundLineString3d lanelet::LaneletSequence::rightBound ( ) const
inline

get the combined right bounds of all lanelets

Definition at line 145 of file LaneletSequence.h.

◆ rightBound2d()

CompoundLineString2d lanelet::LaneletSequence::rightBound2d ( ) const
inline

get the right bound in 2d. To be used over rightBound where geometric calculations are required.

Definition at line 147 of file LaneletSequence.h.

◆ rightBound3d()

CompoundLineString3d lanelet::LaneletSequence::rightBound3d ( ) const
inline

get the combined right bounds of all lanelets

Definition at line 149 of file LaneletSequence.h.

◆ size()

size_t lanelet::LaneletSequence::size ( ) const
inlinenoexcept

Returns number of lanelets.

Definition at line 126 of file LaneletSequence.h.

Member Data Documentation

◆ data_

std::shared_ptr<const LaneletSequenceData> lanelet::LaneletSequence::data_
private

internal data

Definition at line 241 of file LaneletSequence.h.

◆ inverted_

bool lanelet::LaneletSequence::inverted_ {false}
private

Flag that indicates this lanelet is inverted.

Definition at line 242 of file LaneletSequence.h.


The documentation for this class was generated from the following files:


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