Class GenericTrafficRules
Defined in File GenericTrafficRules.h
Inheritance Relationships
Base Type
public lanelet::traffic_rules::TrafficRules
(Class TrafficRules)
Derived Types
public lanelet::traffic_rules::GermanBicycle
(Class GermanBicycle)public lanelet::traffic_rules::GermanPedestrian
(Class GermanPedestrian)public lanelet::traffic_rules::GermanVehicle
(Class GermanVehicle)
Class Documentation
-
class GenericTrafficRules : public lanelet::traffic_rules::TrafficRules
This class generically implements the TrafficRules class in the sense of the tagging specification. It is designed to make sense for most countries and participants. Country specific details (traffic signs, speed limits regulations, …) must be implemented by inheriting classes.
Subclassed by lanelet::traffic_rules::GermanBicycle, lanelet::traffic_rules::GermanPedestrian, lanelet::traffic_rules::GermanVehicle
Public Functions
-
virtual bool canPass(const ConstLanelet &lanelet) const override
returns whether it is allowed to pass/drive on this lanelet
The result can differ by the type of the traffic participant. A sidewalk lanelet is passable for a pedestrian but not for a vehicle. Orientation is important. It is not possible to pass an inverted oneWay Lanelet.
-
virtual bool canPass(const ConstArea &area) const override
returns whether it is allowed to pass/drive on this area
-
virtual bool canPass(const ConstLanelet &from, const ConstLanelet &to) const override
returns whether it is allowed to pass/drive from a lanelet to another lanelet.
The orientation of the lanelets is important. The function first checks if lanelets are direcly adjacent, then checks if both lanelets are passable and finally checks if any traffic rule prevents to pass between the lanelets.
-
virtual bool canPass(const ConstLanelet &from, const ConstArea &to) const override
-
virtual bool canPass(const ConstArea &from, const ConstLanelet &to) const override
-
virtual bool canPass(const ConstArea &from, const ConstArea &to) const override
-
virtual bool canChangeLane(const ConstLanelet &from, const ConstLanelet &to) const override
determines if a lane change can be made between two lanelets
The orientation of the lanelets is important here as well.
-
virtual SpeedLimitInformation speedLimit(const ConstLanelet &lanelet) const override
returns speed limit on this lanelet.
-
virtual SpeedLimitInformation speedLimit(const ConstArea &area) const override
returns speed limit on this area.
-
virtual bool isOneWay(const ConstLanelet &lanelet) const override
returns whether a lanelet can be driven in one direction only
-
virtual bool hasDynamicRules(const ConstLanelet &lanelet) const override
returns whether dynamic traffic rules apply to this lanelet.
This can be a case if e.g. a speed limit is controlled by digital signs. If this returns true, additional handling must be done to find which rules are dynamic and how to handle them. This makes the values returned by the other functions unreliable. Handling of dynamic rules is not covered here.
-
inline explicit TrafficRules(Configuration config = Configuration())
Constructor.
- Parameters:
config – a configuration for traffic rules. This can be necessary for very specialized rule objects (ie considering the time of day or the weather). The config must have at least two entries: participant and location.
Protected Functions
-
virtual Optional<bool> canPass(const RegulatoryElementConstPtrs ®Elems) const = 0
Called by canPass to check if traffic rules make a certain primitive drivable/not drivable If the optional is empty, there is no traffic rule that determines this.
-
virtual Optional<bool> canPass(const std::string &type, const std::string&) const
Called by canPass to check if a certain lanelet type is drivable for this participant.
-
virtual LaneChangeType laneChangeType(const ConstLineString3d &boundary, bool virtualIsPassable) const
checks which types of lange changes are allowed along this boundary to make a lane switch from one lanelet to another.
-
virtual const CountrySpeedLimits &countrySpeedLimits() const = 0
Overloads should return a descripton of their countrie’s speed limit definition.
-
virtual Optional<SpeedLimitInformation> speedLimit(const RegulatoryElementConstPtrs ®elems) const = 0
Returns speed limit as defined by regiualtory elements if present.
-
virtual bool canPass(const ConstLanelet &lanelet) const override