32 #include <lanelet2_core/primitives/Point.h>
37 #include <boost/make_shared.hpp>
38 #include <boost/shared_ptr.hpp>
44 using namespace boost::python;
48 std::string printPoseWrapper(
const Pose2d& p) {
49 std::ostringstream oss;
50 oss <<
"x: " <<
p.translation().x() <<
"\ny: " <<
p.translation().y()
51 <<
"\nphi: " << Eigen::Rotation2Dd(
p.rotation()).angle();
55 boost::shared_ptr<Pose2d> createPose(
const double x,
const double y,
const double phi) {
56 Eigen::Rotation2Dd rot(phi);
57 auto ptr = boost::make_shared<Pose2d>(rot);
58 ptr->translation() = Eigen::Vector2d(x, y);
62 Hull2d hullFromList(
const boost::python::list& l) {
63 Hull2d poly{boost::python::stl_input_iterator<BasicPoint2d>(l), boost::python::stl_input_iterator<BasicPoint2d>()};
67 void clearPythonErrors() {
68 PyObject *ptype, *pvalue, *ptraceback;
69 PyErr_Fetch(&ptype, &pvalue, &ptraceback);
72 object(handle<>(ptype));
75 object(handle<>(pvalue));
78 object(handle<>(ptraceback));
83 std::vector<T> removeNonRuleCompliantMatchesImpl(
const boost::python::list& matchesList,
86 std::vector<T> matchesVector{boost::python::stl_input_iterator<T>(matchesList),
87 boost::python::stl_input_iterator<T>()};
88 return removeNonRuleCompliantMatches<std::vector<T>>(matchesVector, trafficRulesPtr);
91 object ruleCheckWrapper(
const boost::python::list& matches,
94 return object(removeNonRuleCompliantMatchesImpl<ConstLaneletMatchProbabilistic>(matches, trafficRulesPtr));
95 }
catch (
const boost::python::error_already_set&) {
99 return object(removeNonRuleCompliantMatchesImpl<ConstLaneletMatch>(matches, trafficRulesPtr));
100 }
catch (
const boost::python::error_already_set&) {
103 throw std::runtime_error(
"Matches must be a list of ConstLaneletMatch(es) or ConstLaneletMatch(es)Probabilistic");
106 boost::shared_ptr<PositionCovariance2d> covFromVarXVarYCovXY(
const double varX,
const double varY,
const double covXY) {
108 cov << varX, covXY, covXY, varY;
109 return boost::make_shared<PositionCovariance2d>(cov);
112 std::vector<ConstLaneletMatch> (*funcWrapperDeterministic)(
const LaneletMap&,
const Object2d&,
113 const double) = &getDeterministicMatches;
114 std::vector<ConstLaneletMatchProbabilistic> (*funcWrapperProbabilistic)(
const LaneletMap&,
116 const double) = &getProbabilisticMatches;
121 auto core =
import(
"lanelet2.core");
123 class_<Pose2d>(
"Pose2d",
"2D Isometric Transformation", no_init)
125 make_constructor(&createPose, default_call_policies(), (arg(
"x") = 0., arg(
"y") = 0, arg(
"yaw") = 0.)))
126 .def(
"__str__", &printPoseWrapper);
128 class_<Object2d>(
"Object2d",
"Object with pose, hull and ID", no_init)
129 .def(
"__init__", make_constructor(
130 +[](
lanelet::Id objectId,
const Pose2d& pose,
const boost::python::list& absoluteHull) {
131 return boost::make_shared<Object2d>(
Object2d{objectId, pose, hullFromList(absoluteHull)});
133 default_call_policies(),
135 arg(
"absoluteHull") = boost::python::list())))
137 "absoluteHull", +[](
Object2d&
self) {
return self.absoluteHull; }, &hullFromList,
138 "hull in absolute coordinates (not relative to the object's pose)")
139 .def_readwrite(
"pose", &Object2d::pose)
140 .def_readwrite(
"objectId", &Object2d::objectId);
142 class_<PositionCovariance2d>(
"PositionCovariance2d", init<>())
143 .def(
"__init__", make_constructor(&covFromVarXVarYCovXY, default_call_policies(),
144 (arg(
"varX") = 0., arg(
"varY") = 0., arg(
"covXY") = 0.)))
145 .def(self_ns::str(self_ns::self));
147 class_<ObjectWithCovariance2d, bases<Object2d>>(
"ObjectWithCovariance2d",
"Object with pose, covariance, hull and ID",
149 .def(
"__init__", make_constructor(
150 +[](
lanelet::Id objectId,
const Pose2d& pose,
const boost::python::list& absoluteHull,
158 return boost::make_shared<ObjectWithCovariance2d>(obj);
163 default_call_policies(),
165 arg(
"absoluteHull") = boost::python::list(),
167 .def_readwrite(
"vonMisesKappa", &ObjectWithCovariance2d::vonMisesKappa)
168 .def_readwrite(
"positionCovariance", &ObjectWithCovariance2d::positionCovariance);
170 class_<ConstLaneletMatch>(
"ConstLaneletMatch",
"Results from matching objects to lanelets", no_init)
171 .def_readwrite(
"lanelet", &ConstLaneletMatch::lanelet)
172 .def_readwrite(
"distance", &ConstLaneletMatch::distance);
174 class_<ConstLaneletMatchProbabilistic, bases<ConstLaneletMatch>>(
"ConstLaneletMatchProbabilistic",
175 "Results from matching objects to lanelets", no_init)
176 .def_readwrite(
"mahalanobisDistSq", &ConstLaneletMatchProbabilistic::mahalanobisDistSq);
178 VectorToListConverter<std::vector<ConstLaneletMatch>>();
179 VectorToListConverter<std::vector<ConstLaneletMatchProbabilistic>>();
181 def(
"getDeterministicMatches", funcWrapperDeterministic);
182 def(
"getProbabilisticMatches", funcWrapperProbabilistic);
183 def(
"removeNonRuleCompliantMatches", ruleCheckWrapper);