1 #include <lanelet2_core/primitives/Area.h>     6 #include <boost/python.hpp>    30   return self.canPass(llt);
    32 template <
typename T1, 
typename T2>
    34   return self.canPass(from, to);
    45   return TrafficRulesFactory::create(location, participant);
    48 template <const 
char Val[]>
    54   auto core = 
import(
"lanelet2.core");
    56   class_<SpeedLimitInformation>(
"SpeedLimitInformation", 
"Current speed limit as returned by a traffic rule object")
    58            "Initialize from speed limit [m/s] and bool if speedlimit is "    63       .def_readwrite(
"isMandatory", &SpeedLimitInformation::isMandatory,
    64                      "True if speedlimit is not just a recommendation")
    65       .def(self_ns::str(self_ns::self));
    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")
    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));
    89   class_<Locations>(
"Locations").add_static_property(
"Germany", asString<Locations::Germany>);
    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>);
   106       "Create a traffic rules object from location and participant string (see "   107       "Locations and Participants class");
 
SpeedLimitInformation speedLimitWrapper(const TrafficRules &self, const T &llt)
boost::units::quantity< MPS > MPSQuantity
boost::units::unit< boost::units::velocity_dimension, boost::units::si::system > MPS
boost::units::divide_typeof_helper< Km, Hour >::type KmH
bool hasDynamicRulesWrapper(const TrafficRules &self, const ConstLanelet &llt)
TrafficRulesPtr createTrafficRulesWrapper(const std::string &location, const std::string &participant)
void setVelocityMPS(SpeedLimitInformation &self, double velocityMps)
bool canPassWrapper(const TrafficRules &self, const T &llt)
double getVelocityMPS(const SpeedLimitInformation &self)
bool canPassFromToWrapper(const TrafficRules &self, const T1 &from, const T2 &to)
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
void setVelocity(SpeedLimitInformation &self, double velocityKmh)
double getVelocity(const SpeedLimitInformation &self)
SpeedLimitInformation makeSpeedLimit(double speedLimitKph, bool isMandatory)
boost::units::quantity< KmH > KmHQuantity
bool isOneWayWrapper(const TrafficRules &self, const ConstLanelet &llt)
std::shared_ptr< TrafficRules > TrafficRulesPtr
units::MPSQuantity Velocity