Represents a traffic light restriction on the lanelet. More...
#include <BasicRegulatoryElements.h>

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< LineString3d > | stopLine () |
| Optional< ConstLineString3d > | stopLine () 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< ConstRuleParameter > | find (Id id) const |
| template<> | |
| boost::optional< ConstLanelet > | find (Id id) const |
| template<> | |
| boost::optional< ConstArea > | find (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< ConstLanelet > | getParameters (const std::string &role) const |
| template<typename T > | |
| std::vector< T > | getParameters (RoleName role) const |
| template<> | |
| std::vector< ConstLanelet > | getParameters (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 Attribute & | attribute (AttributeName name) const |
| retrieve an attribute (enum version) More... | |
| const Attribute & | attribute (const std::string &name) const |
| retrieve an attribute More... | |
| T | attributeOr (AttributeName name, T defaultVal) const |
| retrieve an attribute (enum version) More... | |
| T | attributeOr (const std::string &name, T defaultVal) const noexcept |
| retrieve an attribute (string version) More... | |
| const AttributeMap & | attributes () 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 |
Friends | |
| class | RegisterRegulatoryElement< TrafficLight > |
Represents a traffic light restriction on the lanelet.
Definition at line 17 of file BasicRegulatoryElements.h.
| using lanelet::TrafficLight::Ptr = std::shared_ptr<TrafficLight> |
Definition at line 19 of file BasicRegulatoryElements.h.
|
protected |
Definition at line 177 of file BasicRegulatoryElements.cpp.
|
explicitprotected |
Definition at line 168 of file BasicRegulatoryElements.cpp.
| void lanelet::TrafficLight::addTrafficLight | ( | const LineStringOrPolygon3d & | primitive | ) |
add a new traffic light
| primitive | the 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.
|
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.
| void lanelet::TrafficLight::removeStopLine | ( | ) |
Deletes the stop line.
Definition at line 203 of file BasicRegulatoryElements.cpp.
| bool lanelet::TrafficLight::removeTrafficLight | ( | const LineStringOrPolygon3d & | primitive | ) |
remove a traffic light
| primitive | the primitive |
Definition at line 197 of file BasicRegulatoryElements.cpp.
| void lanelet::TrafficLight::setStopLine | ( | const LineString3d & | stopLine | ) |
set a new stop line, overwrite the old one
| stopLine | new stop line |
Definition at line 201 of file BasicRegulatoryElements.cpp.
| Optional<LineString3d> lanelet::TrafficLight::stopLine | ( | ) |
| Optional< LineString3d > lanelet::TrafficLight::stopLine | ( | ) | const |
get the stop line for the traffic light
Definition at line 181 of file BasicRegulatoryElements.cpp.
| LineStringsOrPolygons3d lanelet::TrafficLight::trafficLights | ( | ) |
| LineStringsOrPolygons3d lanelet::TrafficLight::trafficLights | ( | ) | const |
get the relevant 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.
|
friend |
Definition at line 71 of file BasicRegulatoryElements.h.
|
staticconstexpr |
Definition at line 20 of file BasicRegulatoryElements.h.