Go to the documentation of this file.
3 #include <lanelet2_core/primitives/Lanelet.h>
8 namespace traffic_rules {
SpeedLimitInformation bicycle
std::unique_ptr< TrafficRules > TrafficRulesUPtr
SpeedLimitInformation vehicleUrbanRoad
Class for inferring traffic rules for lanelets and areas.
SpeedLimitInformation playStreet
SpeedLimitInformation pedestrian
boost::optional< T > Optional
SpeedLimitInformation vehicleNonurbanRoad
virtual const CountrySpeedLimits & countrySpeedLimits() const =0
Overloads should return a descripton of their countrie's speed limit definition.
bool isOneWay(const ConstLanelet &lanelet) const override
returns whether a lanelet can be driven in one direction only
SpeedLimitInformation vehicleNonurbanHighway
SpeedLimitInformation speedLimit(const ConstLanelet &lanelet) const override
returns speed limit on this lanelet.
TrafficRules(Configuration config=Configuration())
Constructor.
SpeedLimitInformation vehicleUrbanHighway
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
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 la...
bool canPass(const ConstLanelet &lanelet) const override
returns whether it is allowed to pass/drive on this lanelet
bool hasDynamicRules(const ConstLanelet &lanelet) const override
returns whether dynamic traffic rules apply to this lanelet.
bool canChangeLane(const ConstLanelet &from, const ConstLanelet &to) const override
determines if a lane change can be made between two lanelets
std::shared_ptr< TrafficRules > TrafficRulesPtr