GenericTrafficRules.h
Go to the documentation of this file.
1 #pragma once
3 #include <lanelet2_core/primitives/Lanelet.h>
4 
6 
7 namespace lanelet {
8 namespace traffic_rules {
9 
19 };
20 
21 class TrafficRules;
22 using TrafficRulesPtr = std::shared_ptr<TrafficRules>;
23 using TrafficRulesUPtr = std::unique_ptr<TrafficRules>;
24 
28 class GenericTrafficRules : public TrafficRules { // NOLINT
29  public:
31 
39  bool canPass(const ConstLanelet& lanelet) const override;
40 
42  bool canPass(const ConstArea& area) const override;
43 
53  bool canPass(const ConstLanelet& from, const ConstLanelet& to) const override;
54  bool canPass(const ConstLanelet& from, const ConstArea& to) const override;
55  bool canPass(const ConstArea& from, const ConstLanelet& to) const override;
56  bool canPass(const ConstArea& from, const ConstArea& to) const override;
57 
63  bool canChangeLane(const ConstLanelet& from, const ConstLanelet& to) const override;
64 
67 
69  SpeedLimitInformation speedLimit(const ConstArea& area) const override;
70 
72  bool isOneWay(const ConstLanelet& lanelet) const override;
73 
82  bool hasDynamicRules(const ConstLanelet& lanelet) const override;
83 
84  protected:
87  virtual Optional<bool> canPass(const RegulatoryElementConstPtrs& regElems) const = 0;
88 
90  virtual Optional<bool> canPass(const std::string& type, const std::string& /*location*/) const;
91 
96  virtual LaneChangeType laneChangeType(const ConstLineString3d& boundary, bool virtualIsPassable) const;
97 
99  virtual const CountrySpeedLimits& countrySpeedLimits() const = 0;
100 
102  virtual Optional<SpeedLimitInformation> speedLimit(const RegulatoryElementConstPtrs& regelems) const = 0;
103 
104  private:
105  SpeedLimitInformation speedLimit(const RegulatoryElementConstPtrs& regelems, const AttributeMap& attributes) const;
106 };
107 } // namespace traffic_rules
108 } // namespace lanelet
lanelet::traffic_rules::CountrySpeedLimits::bicycle
SpeedLimitInformation bicycle
Definition: GenericTrafficRules.h:18
lanelet::traffic_rules::TrafficRulesUPtr
std::unique_ptr< TrafficRules > TrafficRulesUPtr
Definition: GenericTrafficRules.h:23
lanelet::traffic_rules::CountrySpeedLimits::vehicleUrbanRoad
SpeedLimitInformation vehicleUrbanRoad
Definition: GenericTrafficRules.h:12
lanelet
lanelet::traffic_rules::TrafficRules
Class for inferring traffic rules for lanelets and areas.
Definition: TrafficRules.h:18
lanelet::ConstArea
lanelet::traffic_rules::CountrySpeedLimits::playStreet
SpeedLimitInformation playStreet
Definition: GenericTrafficRules.h:16
lanelet::traffic_rules::CountrySpeedLimits
Definition: GenericTrafficRules.h:11
Forward.h
lanelet::traffic_rules::CountrySpeedLimits::pedestrian
SpeedLimitInformation pedestrian
Definition: GenericTrafficRules.h:17
lanelet::Optional
boost::optional< T > Optional
lanelet::traffic_rules::CountrySpeedLimits::vehicleNonurbanRoad
SpeedLimitInformation vehicleNonurbanRoad
Definition: GenericTrafficRules.h:13
lanelet::traffic_rules::GenericTrafficRules::countrySpeedLimits
virtual const CountrySpeedLimits & countrySpeedLimits() const =0
Overloads should return a descripton of their countrie's speed limit definition.
lanelet::traffic_rules::GenericTrafficRules::isOneWay
bool isOneWay(const ConstLanelet &lanelet) const override
returns whether a lanelet can be driven in one direction only
Definition: GenericTrafficRules.cpp:350
lanelet::traffic_rules::CountrySpeedLimits::vehicleNonurbanHighway
SpeedLimitInformation vehicleNonurbanHighway
Definition: GenericTrafficRules.h:15
lanelet::traffic_rules::GenericTrafficRules::speedLimit
SpeedLimitInformation speedLimit(const ConstLanelet &lanelet) const override
returns speed limit on this lanelet.
Definition: GenericTrafficRules.cpp:315
lanelet::traffic_rules::TrafficRules::TrafficRules
TrafficRules(Configuration config=Configuration())
Constructor.
Definition: TrafficRules.h:28
lanelet::traffic_rules::SpeedLimitInformation
Definition: TrafficRules.h:8
lanelet::traffic_rules::LaneChangeType::ToLeft
@ ToLeft
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::traffic_rules::CountrySpeedLimits::vehicleUrbanHighway
SpeedLimitInformation vehicleUrbanHighway
Definition: GenericTrafficRules.h:14
lanelet::RegulatoryElementConstPtrs
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
lanelet::ConstLineString3d
lanelet::traffic_rules::GenericTrafficRules::laneChangeType
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...
Definition: GenericTrafficRules.cpp:161
lanelet::traffic_rules::GenericTrafficRules::canPass
bool canPass(const ConstLanelet &lanelet) const override
returns whether it is allowed to pass/drive on this lanelet
Definition: GenericTrafficRules.cpp:133
lanelet::ConstLanelet
lanelet::traffic_rules::LaneChangeType::Both
@ Both
lanelet::traffic_rules::GenericTrafficRules::hasDynamicRules
bool hasDynamicRules(const ConstLanelet &lanelet) const override
returns whether dynamic traffic rules apply to this lanelet.
Definition: GenericTrafficRules.cpp:127
lanelet::traffic_rules::GenericTrafficRules
Definition: GenericTrafficRules.h:28
lanelet::traffic_rules::LaneChangeType::None
@ None
TrafficRules.h
lanelet::traffic_rules::LaneChangeType::ToRight
@ ToRight
lanelet::traffic_rules::GenericTrafficRules::canChangeLane
bool canChangeLane(const ConstLanelet &from, const ConstLanelet &to) const override
determines if a lane change can be made between two lanelets
Definition: GenericTrafficRules.cpp:248
lanelet::traffic_rules::LaneChangeType
LaneChangeType
Definition: GenericTrafficRules.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