Go to the documentation of this file.
3 #include <lanelet2_core/primitives/Lanelet.h>
6 namespace traffic_rules {
units::MPSQuantity Velocity
virtual SpeedLimitInformation speedLimit(const ConstLanelet &lanelet) const =0
returns speed limit on this lanelet.
std::unique_ptr< TrafficRules > TrafficRulesUPtr
Class for inferring traffic rules for lanelets and areas.
const std::string & location() const
the the location the rules are valid for
virtual bool canChangeLane(const ConstLanelet &from, const ConstLanelet &to) const =0
determines if a lane change can be made between two lanelets
virtual bool canPass(const ConstLanelet &lanelet) const =0
returns whether it is allowed to pass/drive on this lanelet
const Configuration & configuration() const
configuration for this traffic rules object
TrafficRules(Configuration config=Configuration())
Constructor.
std::ostream & operator<<(std::ostream &stream, const SpeedLimitInformation &obj)
const std::string & participant() const
the traffic participant the rules are valid for (e.g. vehicle, car, pedestrian, etc)
virtual bool isOneWay(const ConstLanelet &lanelet) const =0
returns whether a lanelet can be driven in one direction only
std::map< std::string, Attribute > Configuration
virtual bool hasDynamicRules(const ConstLanelet &lanelet) const =0
returns whether dynamic traffic rules apply to this lanelet.
std::shared_ptr< TrafficRules > TrafficRulesPtr