TrafficRules.h
Go to the documentation of this file.
1 #pragma once
3 #include <lanelet2_core/primitives/Lanelet.h>
4 
5 namespace lanelet {
6 namespace traffic_rules {
7 
10  bool isMandatory{true};
11 };
12 
13 class TrafficRules;
14 using TrafficRulesPtr = std::shared_ptr<TrafficRules>;
15 using TrafficRulesUPtr = std::unique_ptr<TrafficRules>;
16 
18 class TrafficRules { // NOLINT
19  public:
20  using Configuration = std::map<std::string, Attribute>;
21 
28  explicit TrafficRules(Configuration config = Configuration()) : config_{std::move(config)} {}
29  virtual ~TrafficRules();
30 
38  virtual bool canPass(const ConstLanelet& lanelet) const = 0;
39 
41  virtual bool canPass(const ConstArea& area) const = 0;
42 
52  virtual bool canPass(const ConstLanelet& from, const ConstLanelet& to) const = 0;
53  virtual bool canPass(const ConstLanelet& from, const ConstArea& to) const = 0;
54  virtual bool canPass(const ConstArea& from, const ConstLanelet& to) const = 0;
55  virtual bool canPass(const ConstArea& from, const ConstArea& to) const = 0;
56 
62  virtual bool canChangeLane(const ConstLanelet& from, const ConstLanelet& to) const = 0;
63 
65  virtual SpeedLimitInformation speedLimit(const ConstLanelet& lanelet) const = 0;
66 
68  virtual SpeedLimitInformation speedLimit(const ConstArea& area) const = 0;
69 
71  virtual bool isOneWay(const ConstLanelet& lanelet) const = 0;
72 
81  virtual bool hasDynamicRules(const ConstLanelet& lanelet) const = 0;
82 
86  const Configuration& configuration() const { return config_; }
87 
92  const std::string& participant() const;
93 
99  const std::string& location() const;
100 
101  private:
103 };
104 
105 std::ostream& operator<<(std::ostream& stream, const SpeedLimitInformation& obj);
106 
107 std::ostream& operator<<(std::ostream& stream, const TrafficRules& obj);
108 
109 } // namespace traffic_rules
110 } // namespace lanelet
lanelet::Velocity
units::MPSQuantity Velocity
lanelet::traffic_rules::TrafficRules::speedLimit
virtual SpeedLimitInformation speedLimit(const ConstLanelet &lanelet) const =0
returns speed limit on this lanelet.
lanelet::traffic_rules::SpeedLimitInformation::speedLimit
Velocity speedLimit
The current speed limit (must not be Inf)
Definition: TrafficRules.h:9
lanelet::traffic_rules::TrafficRulesUPtr
std::unique_ptr< TrafficRules > TrafficRulesUPtr
Definition: GenericTrafficRules.h:23
lanelet
lanelet::traffic_rules::TrafficRules
Class for inferring traffic rules for lanelets and areas.
Definition: TrafficRules.h:18
lanelet::ConstArea
lanelet::traffic_rules::TrafficRules::config_
Configuration config_
Definition: TrafficRules.h:102
lanelet::traffic_rules::TrafficRules::location
const std::string & location() const
the the location the rules are valid for
Definition: GenericTrafficRules.cpp:325
Forward.h
lanelet::traffic_rules::TrafficRules::canChangeLane
virtual bool canChangeLane(const ConstLanelet &from, const ConstLanelet &to) const =0
determines if a lane change can be made between two lanelets
lanelet::traffic_rules::TrafficRules::canPass
virtual bool canPass(const ConstLanelet &lanelet) const =0
returns whether it is allowed to pass/drive on this lanelet
lanelet::traffic_rules::TrafficRules::configuration
const Configuration & configuration() const
configuration for this traffic rules object
Definition: TrafficRules.h:86
lanelet::traffic_rules::TrafficRules::TrafficRules
TrafficRules(Configuration config=Configuration())
Constructor.
Definition: TrafficRules.h:28
TrafficRules
Definition: lanelet2_traffic_rules.cpp:38
lanelet::traffic_rules::operator<<
std::ostream & operator<<(std::ostream &stream, const SpeedLimitInformation &obj)
Definition: GenericTrafficRules.cpp:354
lanelet::traffic_rules::TrafficRules::participant
const std::string & participant() const
the traffic participant the rules are valid for (e.g. vehicle, car, pedestrian, etc)
Definition: GenericTrafficRules.cpp:323
lanelet::traffic_rules::SpeedLimitInformation
Definition: TrafficRules.h:8
lanelet::traffic_rules::TrafficRules::~TrafficRules
virtual ~TrafficRules()
lanelet::traffic_rules::TrafficRules::isOneWay
virtual bool isOneWay(const ConstLanelet &lanelet) const =0
returns whether a lanelet can be driven in one direction only
lanelet::traffic_rules::TrafficRules::Configuration
std::map< std::string, Attribute > Configuration
Definition: TrafficRules.h:20
lanelet::traffic_rules::TrafficRules::hasDynamicRules
virtual bool hasDynamicRules(const ConstLanelet &lanelet) const =0
returns whether dynamic traffic rules apply to this lanelet.
lanelet::ConstLanelet
lanelet::traffic_rules::SpeedLimitInformation::isMandatory
bool isMandatory
False if speed limit is only a recommendation.
Definition: TrafficRules.h:10
lanelet::traffic_rules::TrafficRulesPtr
std::shared_ptr< TrafficRules > TrafficRulesPtr
Definition: GenericTrafficRules.h:22


lanelet2_traffic_rules
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:07