traffic_rules.cpp
Go to the documentation of this file.
1 #include <lanelet2_core/primitives/Area.h>
5 
6 #include <boost/python.hpp>
7 
8 using namespace boost::python;
9 using namespace lanelet;
10 using namespace lanelet::traffic_rules;
11 
12 SpeedLimitInformation makeSpeedLimit(double speedLimitKph, bool isMandatory) {
13  return SpeedLimitInformation{Velocity(speedLimitKph * units::KmH()), isMandatory};
14 }
15 
16 double getVelocity(const SpeedLimitInformation& self) { return units::KmHQuantity(self.speedLimit).value(); }
17 
18 void setVelocity(SpeedLimitInformation& self, double velocityKmh) {
19  self.speedLimit = Velocity(velocityKmh * units::KmH());
20 }
21 
22 double getVelocityMPS(const SpeedLimitInformation& self) { return units::MPSQuantity(self.speedLimit).value(); }
23 
24 void setVelocityMPS(SpeedLimitInformation& self, double velocityMps) {
25  self.speedLimit = Velocity(velocityMps * units::MPS());
26 }
27 
28 template <typename T>
29 bool canPassWrapper(const TrafficRules& self, const T& llt) {
30  return self.canPass(llt);
31 }
32 template <typename T1, typename T2>
33 bool canPassFromToWrapper(const TrafficRules& self, const T1& from, const T2& to) {
34  return self.canPass(from, to);
35 }
36 
37 template <typename T>
39  return self.speedLimit(llt);
40 }
41 bool isOneWayWrapper(const TrafficRules& self, const ConstLanelet& llt) { return self.isOneWay(llt); }
42 bool hasDynamicRulesWrapper(const TrafficRules& self, const ConstLanelet& llt) { return self.hasDynamicRules(llt); }
43 
44 TrafficRulesPtr createTrafficRulesWrapper(const std::string& location, const std::string& participant) {
45  return TrafficRulesFactory::create(location, participant);
46 }
47 
48 template <const char Val[]>
49 std::string asString() {
50  return Val;
51 }
52 
53 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
54  auto core = import("lanelet2.core");
55 
56  class_<SpeedLimitInformation>("SpeedLimitInformation", "Current speed limit as returned by a traffic rule object")
57  .def("__init__", makeSpeedLimit, (arg("speedLimitMPS"), arg("isMandatory") = true),
58  "Initialize from speed limit [m/s] and bool if speedlimit is "
59  "mandatory")
60  .add_property("speedLimit", getVelocity, setVelocity, "velocity in km/h")
61  .add_property("speedLimitKmH", getVelocity, setVelocity, "velocity in km/h")
62  .add_property("speedLimitMPS", getVelocityMPS, setVelocityMPS, "velocity in m/s")
63  .def_readwrite("isMandatory", &SpeedLimitInformation::isMandatory,
64  "True if speedlimit is not just a recommendation")
65  .def(self_ns::str(self_ns::self));
66 
67  class_<TrafficRules, boost::noncopyable, std::shared_ptr<TrafficRules>>("TrafficRules", no_init)
68  .def("canPass", canPassWrapper<ConstLanelet>, "Returns whether it is allowed to pass/drive on this lanelet")
69  .def("canPass", canPassWrapper<ConstArea>, "Returns whether it is allowed to pass/drive on this area")
70  .def("canPass", canPassFromToWrapper<ConstLanelet, ConstLanelet>,
71  "Returns whether it is allowed to drive from first to second lanelet")
72  .def("canPass", canPassFromToWrapper<ConstLanelet, ConstArea>)
73  .def("canPass", canPassFromToWrapper<ConstArea, ConstArea>)
74  .def("canPass", canPassFromToWrapper<ConstArea, ConstLanelet>)
75  .def("canChangeLane", &TrafficRules::canChangeLane,
76  "determines if a lane change can be made between two lanelets")
77  .def("speedLimit", speedLimitWrapper<ConstLanelet>, "get speed limit of this lanelet")
78  .def("speedLimit", speedLimitWrapper<ConstArea>, "get speed limit of this lanelet")
79  .def("isOneWay", isOneWayWrapper, "returns whether a lanelet can be driven in one direction only")
80  .def("hasDynamicRules", hasDynamicRulesWrapper,
81  "returns whether dynamic traffic rules apply to this lanelet that "
82  "can not be understood by this traffic rules object")
83  .def("location", &TrafficRules::location, return_value_policy<copy_const_reference>(),
84  "Location these rules are valid for")
85  .def("participant", &TrafficRules::participant, return_value_policy<copy_const_reference>(),
86  "Participants the rules are valid for")
87  .def(self_ns::str(self_ns::self));
88 
89  class_<Locations>("Locations").add_static_property("Germany", asString<Locations::Germany>);
90 
91  class_<Participants>("Participants")
92  .add_static_property("Vehicle", asString<Participants::Vehicle>)
93  .add_static_property("VehicleCar", asString<Participants::VehicleCar>)
94  .add_static_property("VehicleCarElectric", asString<Participants::VehicleCarElectric>)
95  .add_static_property("VehicleCarCombustion", asString<Participants::VehicleCarCombustion>)
96  .add_static_property("VehicleBus", asString<Participants::VehicleBus>)
97  .add_static_property("VehicleTruck", asString<Participants::VehicleTruck>)
98  .add_static_property("VehicleMotorcycle", asString<Participants::VehicleMotorcycle>)
99  .add_static_property("VehicleTaxi", asString<Participants::VehicleTaxi>)
100  .add_static_property("VehicleEmergency", asString<Participants::VehicleEmergency>)
101  .add_static_property("Bicycle", asString<Participants::Bicycle>)
102  .add_static_property("Pedestrian", asString<Participants::Pedestrian>)
103  .add_static_property("Train", asString<Participants::Train>);
104 
105  def("create", createTrafficRulesWrapper, (arg("location"), arg("participant")),
106  "Create a traffic rules object from location and participant string (see "
107  "Locations and Participants class");
108 }
Velocity
units::MPSQuantity Velocity
lanelet::traffic_rules::SpeedLimitInformation::speedLimit
Velocity speedLimit
speedLimitWrapper
SpeedLimitInformation speedLimitWrapper(const TrafficRules &self, const T &llt)
Definition: traffic_rules.cpp:38
lanelet
location
Primitive ** location
TrafficRulesFactory.h
lanelet::traffic_rules::TrafficRules
makeSpeedLimit
SpeedLimitInformation makeSpeedLimit(double speedLimitKph, bool isMandatory)
Definition: traffic_rules.cpp:12
lanelet::units::MPS
boost::units::unit< boost::units::velocity_dimension, boost::units::si::system > MPS
lanelet::units::KmH
boost::units::divide_typeof_helper< Km, Hour >::type KmH
Units.h
lanelet::units::MPSQuantity
boost::units::quantity< MPS > MPSQuantity
isOneWayWrapper
bool isOneWayWrapper(const TrafficRules &self, const ConstLanelet &llt)
Definition: traffic_rules.cpp:41
lanelet::units::KmHQuantity
boost::units::quantity< KmH > KmHQuantity
getVelocityMPS
double getVelocityMPS(const SpeedLimitInformation &self)
Definition: traffic_rules.cpp:22
canPassWrapper
bool canPassWrapper(const TrafficRules &self, const T &llt)
Definition: traffic_rules.cpp:29
createTrafficRulesWrapper
TrafficRulesPtr createTrafficRulesWrapper(const std::string &location, const std::string &participant)
Definition: traffic_rules.cpp:44
setVelocityMPS
void setVelocityMPS(SpeedLimitInformation &self, double velocityMps)
Definition: traffic_rules.cpp:24
lanelet::traffic_rules
hasDynamicRulesWrapper
bool hasDynamicRulesWrapper(const TrafficRules &self, const ConstLanelet &llt)
Definition: traffic_rules.cpp:42
lanelet::traffic_rules::SpeedLimitInformation
TrafficRules.h
canPassFromToWrapper
bool canPassFromToWrapper(const TrafficRules &self, const T1 &from, const T2 &to)
Definition: traffic_rules.cpp:33
lanelet::ConstLanelet
asString
std::string asString()
Definition: traffic_rules.cpp:49
setVelocity
void setVelocity(SpeedLimitInformation &self, double velocityKmh)
Definition: traffic_rules.cpp:18
getVelocity
double getVelocity(const SpeedLimitInformation &self)
Definition: traffic_rules.cpp:16
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: traffic_rules.cpp:53
TrafficRulesPtr
std::shared_ptr< TrafficRules > TrafficRulesPtr


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:14