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

Common data management class for LaneletSequences. More...

#include <LaneletSequence.h>

Inheritance diagram for lanelet::LaneletSequenceData:
Inheritance graph
[legend]

Public Types

using iterator = internal::ReverseAndForwardIterator< ConstLanelets::const_iterator >
 

Public Member Functions

iterator begin (bool inverted) const noexcept
 
CompoundLineString3d centerline () const
 computes the centerline. Result is cached More...
 
iterator end (bool inverted) const noexcept
 
const ConstLaneletslanelets () const
 
 LaneletSequenceData (ConstLanelets lanelets)
 Constructs a new, valid LaneletData object. More...
 
const CompoundLineString3dleftBound () const
 
CompoundLineString2d leftBound2d () const
 
const CompoundLineString3dleftBound3d () const
 
CompoundPolygon3d polygon () const
 Get the bounding polygon around all lanelets. Result is cached. More...
 
const CompoundLineString3drightBound () const
 
CompoundLineString2d rightBound2d () const
 
const CompoundLineString3drightBound3d () const
 

Private Attributes

std::shared_ptr< CompoundLineString3dcenterline_
 combined centerline More...
 
const ConstLanelets lanelets_
 
const CompoundLineString3d leftBound_
 < Cached data More...
 
std::shared_ptr< CompoundPolygon3dpolygon_
 combined polygon More...
 
const CompoundLineString3d rightBound_
 

Detailed Description

Common data management class for LaneletSequences.

This object is only for internal data management and should not be used directly.

LaneletSequence merely has a shared_ptr to this object and forwards all calls to this object.

Because calculating a polygon and a centerline is expensive, the results are cached by this object.

Definition at line 22 of file LaneletSequence.h.

Member Typedef Documentation

◆ iterator

Definition at line 25 of file LaneletSequence.h.

Constructor & Destructor Documentation

◆ LaneletSequenceData()

lanelet::LaneletSequenceData::LaneletSequenceData ( lanelet::ConstLanelets  lanelets)
explicit

Constructs a new, valid LaneletData object.

See also
ConstLanelet::ConstLanelet

Definition at line 5 of file LaneletSequence.cpp.

Member Function Documentation

◆ begin()

iterator lanelet::LaneletSequenceData::begin ( bool  inverted) const
inlinenoexcept

Definition at line 55 of file LaneletSequence.h.

◆ centerline()

lanelet::CompoundLineString3d lanelet::LaneletSequenceData::centerline ( ) const

computes the centerline. Result is cached

Returns
centerline object. Can not be modified.
See also
ConstLanelet::centerline

Definition at line 10 of file LaneletSequence.cpp.

◆ end()

iterator lanelet::LaneletSequenceData::end ( bool  inverted) const
inlinenoexcept

Definition at line 59 of file LaneletSequence.h.

◆ lanelets()

const ConstLanelets& lanelet::LaneletSequenceData::lanelets ( ) const
inline

Definition at line 39 of file LaneletSequence.h.

◆ leftBound()

const CompoundLineString3d& lanelet::LaneletSequenceData::leftBound ( ) const
inline

Definition at line 32 of file LaneletSequence.h.

◆ leftBound2d()

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

Definition at line 34 of file LaneletSequence.h.

◆ leftBound3d()

const CompoundLineString3d& lanelet::LaneletSequenceData::leftBound3d ( ) const
inline

Definition at line 33 of file LaneletSequence.h.

◆ polygon()

lanelet::CompoundPolygon3d lanelet::LaneletSequenceData::polygon ( ) const

Get the bounding polygon around all lanelets. Result is cached.

Returns
a polygon object. Can not be modified.
See also
ConstLanelet::polygon

Definition at line 20 of file LaneletSequence.cpp.

◆ rightBound()

const CompoundLineString3d& lanelet::LaneletSequenceData::rightBound ( ) const
inline

Definition at line 36 of file LaneletSequence.h.

◆ rightBound2d()

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

Definition at line 38 of file LaneletSequence.h.

◆ rightBound3d()

const CompoundLineString3d& lanelet::LaneletSequenceData::rightBound3d ( ) const
inline

Definition at line 37 of file LaneletSequence.h.

Member Data Documentation

◆ centerline_

std::shared_ptr<CompoundLineString3d> lanelet::LaneletSequenceData::centerline_
mutableprivate

combined centerline

Definition at line 68 of file LaneletSequence.h.

◆ lanelets_

const ConstLanelets lanelet::LaneletSequenceData::lanelets_
private

Definition at line 64 of file LaneletSequence.h.

◆ leftBound_

const CompoundLineString3d lanelet::LaneletSequenceData::leftBound_
private

< Cached data

Definition at line 66 of file LaneletSequence.h.

◆ polygon_

std::shared_ptr<CompoundPolygon3d> lanelet::LaneletSequenceData::polygon_
mutableprivate

combined polygon

Definition at line 69 of file LaneletSequence.h.

◆ rightBound_

const CompoundLineString3d lanelet::LaneletSequenceData::rightBound_
private

Definition at line 67 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