Class TrafficSign
Defined in File BasicRegulatoryElements.h
Inheritance Relationships
Base Type
public lanelet::RegulatoryElement
(Class RegulatoryElement)
Derived Type
public lanelet::SpeedLimit
(Class SpeedLimit)
Class Documentation
-
class TrafficSign : public lanelet::RegulatoryElement
Expresses a generic traffic sign rule.
Subclassed by lanelet::SpeedLimit
Public Types
-
using Ptr = std::shared_ptr<TrafficSign>
Public Functions
-
ConstLineStringsOrPolygons3d trafficSigns() const
returns the traffic signs
There might be multiple but they are all required to show the same symbol.
-
LineStringsOrPolygons3d trafficSigns()
-
std::string type() const
get the id/number of the sign(s)
The id is in the format [country-code][ID], e.g. de205. The result can be dependant on country
-
ConstLineStrings3d refLines() const
gets the line(s) from which a sign becomes valid.
There might or might not be such a line. If there is none, the sign is valid for the whole lanelet
-
LineStrings3d refLines()
-
ConstLineStringsOrPolygons3d cancellingTrafficSigns() const
get list of cancellingTrafficSigns, if existing
-
LineStringsOrPolygons3d cancellingTrafficSigns()
-
std::vector<std::string> cancelTypes() const
Types of the cancelling traffic signs if they exist.
-
ConstLineStrings3d cancelLines() const
gets the line(s) from which a sign becomes invalid.
-
LineStrings3d cancelLines()
-
void 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.
-
bool removeTrafficSign(const LineStringOrPolygon3d &sign)
remove a traffic sign and returns true on success
-
void addCancellingTrafficSign(const TrafficSignsWithType &signs)
Add new cancelling traffic sign.
-
bool removeCancellingTrafficSign(const LineStringOrPolygon3d &sign)
remove a cancelling traffic sign, returns true on success
-
void addRefLine(const LineString3d &line)
Add a new reference line.
-
bool removeRefLine(const LineString3d &line)
Remove a reference line. Returns true on success.
-
void addCancellingRefLine(const LineString3d &line)
Add a new line from where the sign becomes inactive.
-
bool removeCancellingRefLine(const LineString3d &line)
Remove a cancelling line. Returns true on success.
Public Static Functions
-
static inline Ptr make(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns = {}, const LineStrings3d &refLines = {}, const LineStrings3d &cancelLines = {})
Create a valid TrafficSign object.
A traffic sign is usually composed of a set of traffic signs of the same type that mark the beginning of the rule. It also contains multiple traffic signs (potentially of different types) that mark the end of the rule. E.g. a 50kph section would contain all 50kph signs of this section as trafficSigns. All signs that stand at the end of this section (e.g. a 70kph sign and an end of 50kph sign) would be cancellingTrafficSigns.
- Parameters:
id – id of traffic sign rule
attributes – attributes for it (might be extended if necessary)
trafficSigns – list of the traffic signs defining the rule
cancellingTrafficSigns – list of traffic signs where the rule is cancelled. Can be empty.
refLines – lines from where the rule becomes valid. Can be empty.
cancelLines – lines after which a rule becomes invalid. Can be empty.
Public Static Attributes
-
static constexpr char RuleName[] = "traffic_sign"
Protected Functions
-
TrafficSign(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns = {}, const LineStrings3d &refLines = {}, const LineStrings3d &cancelLines = {})
-
explicit TrafficSign(const RegulatoryElementDataPtr &data)
Friends
- friend class RegisterRegulatoryElement< TrafficSign >
-
using Ptr = std::shared_ptr<TrafficSign>