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

Represents a traffic light restriction on the lanelet. More...

#include <BasicRegulatoryElements.h>

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

Public Types

using Ptr = std::shared_ptr< TrafficLight >
 
- 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 addTrafficLight (const LineStringOrPolygon3d &primitive)
 add a new traffic light More...
 
void removeStopLine ()
 Deletes the stop line. More...
 
bool removeTrafficLight (const LineStringOrPolygon3d &primitive)
 remove a traffic light More...
 
void setStopLine (const LineString3d &stopLine)
 set a new stop line, overwrite the old one More...
 
Optional< LineString3dstopLine ()
 
Optional< ConstLineString3dstopLine () const
 get the stop line for the traffic light More...
 
LineStringsOrPolygons3d trafficLights ()
 
ConstLineStringsOrPolygons3d trafficLights () const
 get the relevant traffic lights 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 LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
 

Static Public Attributes

static constexpr char RuleName [] = "traffic_light"
 
- 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

 TrafficLight (const RegulatoryElementDataPtr &data)
 
 TrafficLight (Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine)
 
- 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< TrafficLight >
 

Detailed Description

Represents a traffic light restriction on the lanelet.

Definition at line 17 of file BasicRegulatoryElements.h.

Member Typedef Documentation

◆ Ptr

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

Definition at line 19 of file BasicRegulatoryElements.h.

Constructor & Destructor Documentation

◆ TrafficLight() [1/2]

lanelet::TrafficLight::TrafficLight ( Id  id,
const AttributeMap attributes,
const LineStringsOrPolygons3d trafficLights,
const Optional< LineString3d > &  stopLine 
)
protected

Definition at line 177 of file BasicRegulatoryElements.cpp.

◆ TrafficLight() [2/2]

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

Definition at line 168 of file BasicRegulatoryElements.cpp.

Member Function Documentation

◆ addTrafficLight()

void lanelet::TrafficLight::addTrafficLight ( const LineStringOrPolygon3d primitive)

add a new traffic light

Parameters
primitivethe traffic light to add

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

Definition at line 193 of file BasicRegulatoryElements.cpp.

◆ make()

static Ptr lanelet::TrafficLight::make ( Id  id,
const AttributeMap attributes,
const LineStringsOrPolygons3d trafficLights,
const Optional< LineString3d > &  stopLine = {} 
)
inlinestatic

Directly construct a stop line from its required rule parameters. Might modify the input data in oder to get correct tags.

Definition at line 23 of file BasicRegulatoryElements.h.

◆ removeStopLine()

void lanelet::TrafficLight::removeStopLine ( )

Deletes the stop line.

Definition at line 203 of file BasicRegulatoryElements.cpp.

◆ removeTrafficLight()

bool lanelet::TrafficLight::removeTrafficLight ( const LineStringOrPolygon3d primitive)

remove a traffic light

Parameters
primitivethe primitive
Returns
true if the traffic light existed and was removed

Definition at line 197 of file BasicRegulatoryElements.cpp.

◆ setStopLine()

void lanelet::TrafficLight::setStopLine ( const LineString3d stopLine)

set a new stop line, overwrite the old one

Parameters
stopLinenew stop line

Definition at line 201 of file BasicRegulatoryElements.cpp.

◆ stopLine() [1/2]

Optional<LineString3d> lanelet::TrafficLight::stopLine ( )

◆ stopLine() [2/2]

Optional< LineString3d > lanelet::TrafficLight::stopLine ( ) const

get the stop line for the traffic light

Returns
the stop line as LineString

Definition at line 181 of file BasicRegulatoryElements.cpp.

◆ trafficLights() [1/2]

LineStringsOrPolygons3d lanelet::TrafficLight::trafficLights ( )

◆ trafficLights() [2/2]

LineStringsOrPolygons3d lanelet::TrafficLight::trafficLights ( ) const

get the relevant traffic lights

Returns
the traffic lights

There might be multiple traffic lights but they are required to show the same signal.

Definition at line 187 of file BasicRegulatoryElements.cpp.

Friends And Related Function Documentation

◆ RegisterRegulatoryElement< TrafficLight >

friend class RegisterRegulatoryElement< TrafficLight >
friend

Definition at line 71 of file BasicRegulatoryElements.h.

Member Data Documentation

◆ RuleName

constexpr char lanelet::TrafficLight::RuleName = "traffic_light"
staticconstexpr

Definition at line 20 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:53