Class AutowareTrafficLight
Defined in File autoware_traffic_light.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public lanelet::TrafficLight
Class Documentation
-
class AutowareTrafficLight : public lanelet::TrafficLight
Public Types
-
using Ptr = std::shared_ptr<AutowareTrafficLight>
Public Functions
-
ConstLineStrings3d lightBulbs() const
get the relevant traffic light bulbs
There might be multiple traffic light bulbs but they are required to show the same signal.
- Returns:
the traffic light bulbs
-
void addLightBulbs(const LineStringOrPolygon3d &primitive)
add a new traffic light bulb
Traffic light bulbs are represented as linestrings with each point expressing position of each light bulb (lamp).
- Parameters:
primitive – the traffic light bulb to add
-
bool removeLightBulbs(const LineStringOrPolygon3d &primitive)
remove a traffic light bulb
- Parameters:
primitive – the primitive
- Returns:
true if the traffic light bulb existed and was removed
Public Static Functions
-
static inline Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional<LineString3d> &stopLine = {}, const LineStrings3d &lightBulbs = {})
Directly construct a stop line from its required rule parameters. Might modify the input data in oder to get correct tags.
Public Static Attributes
-
static constexpr char RuleName[] = "traffic_light"
-
using Ptr = std::shared_ptr<AutowareTrafficLight>