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

A lanelet path represents a set of lanelets that can be reached in order by either driving straight or doing lane changes. More...

#include <LaneletPath.h>

Public Types

using const_iterator = ConstLanelets::const_iterator
 
using iterator = ConstLanelets::iterator
 

Public Member Functions

const ConstLaneletback () const
 
iterator begin ()
 
const_iterator begin () const
 
bool empty () const
 
iterator end ()
 
const_iterator end () const
 
const ConstLaneletfront () const
 
LaneletSequence getRemainingLane (const ConstLanelet &llt) const
 
LaneletSequence getRemainingLane (const_iterator laneletPosition) const
 Returns all succeeding lanelets from the current position that can be reached without changing lanes. More...
 
 LaneletPath (ConstLanelets lanelets={})
 
bool operator!= (const LaneletPath &other) const
 
bool operator== (const LaneletPath &other) const
 
const ConstLaneletoperator[] (size_t idx) const
 
size_t size () const
 

Private Attributes

ConstLanelets lanelets_
 

Detailed Description

A lanelet path represents a set of lanelets that can be reached in order by either driving straight or doing lane changes.

Definition at line 13 of file LaneletPath.h.

Member Typedef Documentation

◆ const_iterator

using lanelet::routing::LaneletPath::const_iterator = ConstLanelets::const_iterator

Definition at line 16 of file LaneletPath.h.

◆ iterator

using lanelet::routing::LaneletPath::iterator = ConstLanelets::iterator

Definition at line 15 of file LaneletPath.h.

Constructor & Destructor Documentation

◆ LaneletPath()

lanelet::routing::LaneletPath::LaneletPath ( ConstLanelets  lanelets = {})
inlineexplicit

Definition at line 18 of file LaneletPath.h.

Member Function Documentation

◆ back()

const ConstLanelet& lanelet::routing::LaneletPath::back ( ) const
inline

Definition at line 27 of file LaneletPath.h.

◆ begin() [1/2]

iterator lanelet::routing::LaneletPath::begin ( )
inline

Definition at line 20 of file LaneletPath.h.

◆ begin() [2/2]

const_iterator lanelet::routing::LaneletPath::begin ( ) const
inline

Definition at line 21 of file LaneletPath.h.

◆ empty()

bool lanelet::routing::LaneletPath::empty ( ) const
inline

Definition at line 25 of file LaneletPath.h.

◆ end() [1/2]

iterator lanelet::routing::LaneletPath::end ( )
inline

Definition at line 22 of file LaneletPath.h.

◆ end() [2/2]

const_iterator lanelet::routing::LaneletPath::end ( ) const
inline

Definition at line 23 of file LaneletPath.h.

◆ front()

const ConstLanelet& lanelet::routing::LaneletPath::front ( ) const
inline

Definition at line 26 of file LaneletPath.h.

◆ getRemainingLane() [1/2]

LaneletSequence lanelet::routing::LaneletPath::getRemainingLane ( const ConstLanelet llt) const
inline

Definition at line 40 of file LaneletPath.h.

◆ getRemainingLane() [2/2]

LaneletSequence lanelet::routing::LaneletPath::getRemainingLane ( LaneletPath::const_iterator  laneletPosition) const

Returns all succeeding lanelets from the current position that can be reached without changing lanes.

Definition at line 326 of file LaneletPath.cpp.

◆ operator!=()

bool lanelet::routing::LaneletPath::operator!= ( const LaneletPath other) const
inline

Definition at line 33 of file LaneletPath.h.

◆ operator==()

bool lanelet::routing::LaneletPath::operator== ( const LaneletPath other) const
inline

Definition at line 35 of file LaneletPath.h.

◆ operator[]()

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

Definition at line 28 of file LaneletPath.h.

◆ size()

size_t lanelet::routing::LaneletPath::size ( ) const
inline

Definition at line 24 of file LaneletPath.h.

Member Data Documentation

◆ lanelets_

ConstLanelets lanelet::routing::LaneletPath::lanelets_
private

Definition at line 45 of file LaneletPath.h.


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


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49