#include <GenericTrafficRules.h>

Public Member Functions | |
| bool | canChangeLane (const ConstLanelet &from, const ConstLanelet &to) const override |
| determines if a lane change can be made between two lanelets More... | |
| bool | canPass (const ConstArea &area) const override |
| returns whether it is allowed to pass/drive on this area More... | |
| bool | canPass (const ConstArea &from, const ConstArea &to) const override |
| bool | canPass (const ConstArea &from, const ConstLanelet &to) const override |
| bool | canPass (const ConstLanelet &from, const ConstArea &to) const override |
| bool | canPass (const ConstLanelet &from, const ConstLanelet &to) const override |
| returns whether it is allowed to pass/drive from a lanelet to another lanelet. More... | |
| bool | canPass (const ConstLanelet &lanelet) const override |
| returns whether it is allowed to pass/drive on this lanelet More... | |
| bool | hasDynamicRules (const ConstLanelet &lanelet) const override |
| returns whether dynamic traffic rules apply to this lanelet. More... | |
| bool | isOneWay (const ConstLanelet &lanelet) const override |
| returns whether a lanelet can be driven in one direction only More... | |
| SpeedLimitInformation | speedLimit (const ConstArea &area) const override |
| returns speed limit on this area. More... | |
| SpeedLimitInformation | speedLimit (const ConstLanelet &lanelet) const override |
| returns speed limit on this lanelet. More... | |
| TrafficRules (Configuration config=Configuration()) | |
| Constructor. More... | |
Public Member Functions inherited from lanelet::traffic_rules::TrafficRules | |
| const Configuration & | configuration () const |
| configuration for this traffic rules object More... | |
| const std::string & | location () const |
| the the location the rules are valid for More... | |
| const std::string & | participant () const |
| the traffic participant the rules are valid for (e.g. vehicle, car, pedestrian, etc) More... | |
| TrafficRules (Configuration config=Configuration()) | |
| Constructor. More... | |
| virtual | ~TrafficRules () |
Protected Member Functions | |
| virtual Optional< bool > | canPass (const RegulatoryElementConstPtrs ®Elems) const =0 |
| 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. More... | |
| virtual const CountrySpeedLimits & | countrySpeedLimits () const =0 |
| Overloads should return a descripton of their countrie's speed limit definition. More... | |
| 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. More... | |
| virtual Optional< SpeedLimitInformation > | speedLimit (const RegulatoryElementConstPtrs ®elems) const =0 |
| Returns speed limit as defined by regiualtory elements if present. More... | |
Private Member Functions | |
| SpeedLimitInformation | speedLimit (const RegulatoryElementConstPtrs ®elems, const AttributeMap &attributes) const |
Additional Inherited Members | |
Public Types inherited from lanelet::traffic_rules::TrafficRules | |
| using | Configuration = std::map< std::string, Attribute > |
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.
Definition at line 28 of file GenericTrafficRules.h.
|
overridevirtual |
determines if a lane change can be made between two lanelets
The orientation of the lanelets is important here as well.
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 248 of file GenericTrafficRules.cpp.
|
overridevirtual |
returns whether it is allowed to pass/drive on this area
Implements lanelet::traffic_rules::TrafficRules.
Reimplemented in lanelet::traffic_rules::GermanVehicle.
Definition at line 149 of file GenericTrafficRules.cpp.
|
overridevirtual |
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 237 of file GenericTrafficRules.cpp.
|
overridevirtual |
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 220 of file GenericTrafficRules.cpp.
|
overridevirtual |
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 203 of file GenericTrafficRules.cpp.
|
overridevirtual |
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.
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 187 of file GenericTrafficRules.cpp.
|
overridevirtual |
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.
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 133 of file GenericTrafficRules.cpp.
|
protectedpure virtual |
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.
Implemented in lanelet::traffic_rules::GermanBicycle, lanelet::traffic_rules::GermanPedestrian, and lanelet::traffic_rules::GermanVehicle.
|
protectedvirtual |
Called by canPass to check if a certain lanelet type is drivable for this participant.
Definition at line 327 of file GenericTrafficRules.cpp.
|
protectedpure virtual |
Overloads should return a descripton of their countrie's speed limit definition.
Implemented in lanelet::traffic_rules::GermanBicycle, lanelet::traffic_rules::GermanPedestrian, and lanelet::traffic_rules::GermanVehicle.
|
overridevirtual |
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.
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 127 of file GenericTrafficRules.cpp.
|
overridevirtual |
returns whether a lanelet can be driven in one direction only
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 350 of file GenericTrafficRules.cpp.
|
protectedvirtual |
checks which types of lange changes are allowed along this boundary to make a lane switch from one lanelet to another.
Definition at line 161 of file GenericTrafficRules.cpp.
|
overridevirtual |
returns speed limit on this area.
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 319 of file GenericTrafficRules.cpp.
|
overridevirtual |
returns speed limit on this lanelet.
Implements lanelet::traffic_rules::TrafficRules.
Definition at line 315 of file GenericTrafficRules.cpp.
|
protectedpure virtual |
Returns speed limit as defined by regiualtory elements if present.
Implemented in lanelet::traffic_rules::GermanVehicle, lanelet::traffic_rules::GermanBicycle, and lanelet::traffic_rules::GermanPedestrian.
|
private |
Definition at line 294 of file GenericTrafficRules.cpp.
|
inlineexplicit |
Constructor.
| 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. |
Definition at line 28 of file TrafficRules.h.