Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Friends | List of all members
lanelet::AllWayStop Class Reference

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...

#include <BasicRegulatoryElements.h>

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

Public Types

using Ptr = std::shared_ptr< AllWayStop >
 
- Public Types inherited from lanelet::RegulatoryElement
using Category = traits::RegulatoryElementTag
 
using const_iterator = RuleParameterMap::const_iterator
 
using ConstType = RegulatoryElement
 
using iterator = RuleParameterMap::iterator
 
using MutableType = GenericRegulatoryElement
 
using ThreeDType = RegulatoryElement
 
using TwoDType = RegulatoryElement
 
- Public Types inherited from lanelet::ConstPrimitive< RegulatoryElementData >
using DataType = RegulatoryElementData
 

Public Member Functions

void addLanelet (const LaneletWithStopLine &lltWithStop)
 
void addTrafficSign (const LineStringOrPolygon3d &sign)
 Adds another traffic sign. More...
 
Optional< LineString3dgetStopLine (const ConstLanelet &llt)
 
Optional< ConstLineString3dgetStopLine (const ConstLanelet &llt) const
 gets the stop line for a lanelet, if there is one More...
 
Lanelets lanelets ()
 
ConstLanelets lanelets () const
 get the lanelets that potentially have to yield More...
 
bool removeLanelet (const Lanelet &llt)
 Removes a lanelet and the associated stop line, if there is one. More...
 
bool removeTrafficSign (const LineStringOrPolygon3d &sign)
 removes a traffic sign and returns true on success More...
 
LineStrings3d stopLines ()
 
ConstLineStrings3d stopLines () const
 get the stop lines More...
 
LineStringsOrPolygons3d trafficSigns ()
 
ConstLineStringsOrPolygons3d trafficSigns () const
 get list of traffic signs that constitute this AllWayStop if existing More...
 
- Public Member Functions inherited from lanelet::RegulatoryElement
void applyVisitor (RuleParameterVisitor &visitor) const
 applies a visitor to every parameter in the regulatory element More...
 
bool empty () const
 returns true if this object contains no parameters More...
 
template<typename T >
Optional< T > find (Id id) const
 Finds a parameter by its id, independent of the role. More...
 
template<>
Optional< ConstRuleParameterfind (Id id) const
 
template<>
boost::optional< ConstLaneletfind (Id id) const
 
template<>
boost::optional< ConstAreafind (Id id) const
 
ConstRuleParameterMap getParameters () const
 Returns all parameters as const object (coversion overhead for const) More...
 
template<typename T >
std::vector< T > getParameters (const std::string &role) const
 Returns a vector of all RuleParameters that could be converted to T. More...
 
template<>
std::vector< ConstLaneletgetParameters (const std::string &role) const
 
template<typename T >
std::vector< T > getParameters (RoleName role) const
 
template<>
std::vector< ConstLaneletgetParameters (RoleName role) const
 
std::vector< std::string > roles () const
 returns all the roles this regulatory element has More...
 
void setId (Id id) noexcept
 
size_t size () const
 get the number of roles in this regulatoryElement More...
 
virtual ~RegulatoryElement ()
 
- Public Member Functions inherited from lanelet::ConstPrimitive< RegulatoryElementData >
const Attributeattribute (AttributeName name) const
 retrieve an attribute (enum version) More...
 
const Attributeattribute (const std::string &name) const
 retrieve an attribute More...
 
attributeOr (AttributeName name, T defaultVal) const
 retrieve an attribute (enum version) More...
 
attributeOr (const std::string &name, T defaultVal) const noexcept
 retrieve an attribute (string version) More...
 
const AttributeMapattributes () const
 get the attributes of this primitive More...
 
const std::shared_ptr< const RegulatoryElementData > & constData () const
 get the internal data of this primitive More...
 
 ConstPrimitive (const std::shared_ptr< const RegulatoryElementData > &data)
 Construct from a pointer to the data. More...
 
bool hasAttribute (AttributeName name) const noexcept
 check for an attribute (enum version) More...
 
bool hasAttribute (const std::string &name) const noexcept
 check whether this primitive has a specific attribute More...
 
Id id () const noexcept
 get the unique id of this primitive More...
 
bool operator!= (const ConstPrimitive &rhs) const
 
bool operator== (const ConstPrimitive &rhs) const
 

Static Public Member Functions

static Ptr make (Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs={})
 Create a valid all way stop object. More...
 

Static Public Attributes

static constexpr char RuleName [] = "all_way_stop"
 
- Static Public Attributes inherited from lanelet::RegulatoryElement
static constexpr char RuleName [] = "basic_regulatory_element"
 
- Static Public Attributes inherited from lanelet::ConstPrimitive< RegulatoryElementData >
static constexpr bool IsConst
 

Protected Member Functions

 AllWayStop (const RegulatoryElementDataPtr &data)
 
 AllWayStop (Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs)
 
- Protected Member Functions inherited from lanelet::RegulatoryElement
void applyVisitor (internal::MutableParameterVisitor &visitor) const
 
const_iterator begin () const
 
RegulatoryElementDataPtr data ()
 
const_iterator end () const
 
template<typename T >
std::vector< T > getParameters (RoleName role)
 
RuleParameterMapparameters ()
 
const RuleParameterMapparameters () const
 
 RegulatoryElement (const RegulatoryElementDataPtr &data)
 
 RegulatoryElement (Id id=InvalId, const RuleParameterMap &members=RuleParameterMap(), const AttributeMap &attributes=AttributeMap())
 
- Protected Member Functions inherited from lanelet::ConstPrimitive< RegulatoryElementData >
 ConstPrimitive (const ConstPrimitive &rhs)=default
 
 ConstPrimitive (ConstPrimitive &&rhs) noexcept=default
 
ConstPrimitiveoperator= (const ConstPrimitive &rhs)=default
 
ConstPrimitiveoperator= (ConstPrimitive &&rhs) noexcept=default
 
 ~ConstPrimitive () noexcept=default
 

Friends

class RegisterRegulatoryElement< AllWayStop >
 

Detailed Description

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.

The distance to the intersection is represented either by the distance to the stop line, if present, otherwise the distance to the end of the lanelet.

Definition at line 163 of file BasicRegulatoryElements.h.

Member Typedef Documentation

◆ Ptr

using lanelet::AllWayStop::Ptr = std::shared_ptr<AllWayStop>

Definition at line 165 of file BasicRegulatoryElements.h.

Constructor & Destructor Documentation

◆ AllWayStop() [1/2]

lanelet::AllWayStop::AllWayStop ( Id  id,
const AttributeMap attributes,
const LaneletsWithStopLines lltsWithStop,
const LineStringsOrPolygons3d signs 
)
protected

Definition at line 449 of file BasicRegulatoryElements.cpp.

◆ AllWayStop() [2/2]

lanelet::AllWayStop::AllWayStop ( const RegulatoryElementDataPtr data)
explicitprotected

Definition at line 453 of file BasicRegulatoryElements.cpp.

Member Function Documentation

◆ addLanelet()

void lanelet::AllWayStop::addLanelet ( const LaneletWithStopLine lltWithStop)

Adds a new lanelet with stop line. This will throw if the other lanelets did not have a stop line and vice versa

Exceptions
InvalidInputErrorif stop line is inconsistent

Definition at line 417 of file BasicRegulatoryElements.cpp.

◆ addTrafficSign()

void lanelet::AllWayStop::addTrafficSign ( const LineStringOrPolygon3d sign)

Adds another traffic sign.

Traffic signs are represented as linestrings that start at the left edge and end at the right edge of a traffic sign.

Definition at line 409 of file BasicRegulatoryElements.cpp.

◆ getStopLine() [1/2]

Optional< LineString3d > lanelet::AllWayStop::getStopLine ( const ConstLanelet llt)

Definition at line 390 of file BasicRegulatoryElements.cpp.

◆ getStopLine() [2/2]

Optional< ConstLineString3d > lanelet::AllWayStop::getStopLine ( const ConstLanelet llt) const

gets the stop line for a lanelet, if there is one

Definition at line 377 of file BasicRegulatoryElements.cpp.

◆ lanelets() [1/2]

Lanelets lanelet::AllWayStop::lanelets ( )

◆ lanelets() [2/2]

Lanelets lanelet::AllWayStop::lanelets ( ) const

get the lanelets that potentially have to yield

Definition at line 369 of file BasicRegulatoryElements.cpp.

◆ make()

static Ptr lanelet::AllWayStop::make ( Id  id,
const AttributeMap attributes,
const LaneletsWithStopLines lltsWithStop,
const LineStringsOrPolygons3d signs = {} 
)
inlinestatic

Create a valid all way stop object.

Parameters
idid for this rule
attributesfor this rule. Might be extended if necessary
lltsWithStoplanelets with stop line. Either all lanelets have a stop line or none.
signstraffic signs that constitute this rule

Definition at line 175 of file BasicRegulatoryElements.h.

◆ removeLanelet()

bool lanelet::AllWayStop::removeLanelet ( const Lanelet llt)

Removes a lanelet and the associated stop line, if there is one.

Definition at line 431 of file BasicRegulatoryElements.cpp.

◆ removeTrafficSign()

bool lanelet::AllWayStop::removeTrafficSign ( const LineStringOrPolygon3d sign)

removes a traffic sign and returns true on success

Definition at line 413 of file BasicRegulatoryElements.cpp.

◆ stopLines() [1/2]

LineStrings3d lanelet::AllWayStop::stopLines ( )

◆ stopLines() [2/2]

LineStrings3d lanelet::AllWayStop::stopLines ( ) const

get the stop lines

Definition at line 373 of file BasicRegulatoryElements.cpp.

◆ trafficSigns() [1/2]

LineStringsOrPolygons3d lanelet::AllWayStop::trafficSigns ( )

◆ trafficSigns() [2/2]

LineStringsOrPolygons3d lanelet::AllWayStop::trafficSigns ( ) const

get list of traffic signs that constitute this AllWayStop if existing

Definition at line 403 of file BasicRegulatoryElements.cpp.

Friends And Related Function Documentation

◆ RegisterRegulatoryElement< AllWayStop >

friend class RegisterRegulatoryElement< AllWayStop >
friend

Definition at line 213 of file BasicRegulatoryElements.h.

Member Data Documentation

◆ RuleName

constexpr char lanelet::AllWayStop::RuleName = "all_way_stop"
staticconstexpr

Definition at line 166 of file BasicRegulatoryElements.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