matching.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020
3  * FZI Forschungszentrum Informatik, Karlsruhe, Germany (www.fzi.de)
4  * KIT, Institute of Measurement and Control, Karlsruhe, Germany (www.mrt.kit.edu)
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  * 2. Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its contributors
16  * may be used to endorse or promote products derived from this software without
17  * specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  */
30 
32 #include <lanelet2_core/primitives/Point.h>
36 
37 #include <boost/make_shared.hpp>
38 #include <boost/shared_ptr.hpp>
39 #include <iostream>
40 
42 
43 namespace {
44 using namespace boost::python;
45 using namespace lanelet;
46 using namespace lanelet::matching;
47 
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();
52  return oss.str();
53 }
54 
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);
59  return ptr;
60 }
61 
62 Hull2d hullFromList(const boost::python::list& l) {
63  Hull2d poly{boost::python::stl_input_iterator<BasicPoint2d>(l), boost::python::stl_input_iterator<BasicPoint2d>()};
64  return poly;
65 }
66 
67 void clearPythonErrors() {
68  PyObject *ptype, *pvalue, *ptraceback; // NOLINT
69  PyErr_Fetch(&ptype, &pvalue, &ptraceback);
70  // create boost python objects from objects behind pointer, such that python does garbage collection
71  if (!!ptype) { // NOLINT
72  object(handle<>(ptype));
73  }
74  if (!!pvalue) { // NOLINT
75  object(handle<>(pvalue));
76  }
77  if (!!ptraceback) { // NOLINT
78  object(handle<>(ptraceback));
79  }
80 }
81 
82 template <typename T>
83 std::vector<T> removeNonRuleCompliantMatchesImpl(const boost::python::list& matchesList,
84  const lanelet::traffic_rules::TrafficRulesPtr& trafficRulesPtr) {
85  // convert list to a vector of type T (throws a python exception if not possible)
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);
89 }
90 
91 object ruleCheckWrapper(const boost::python::list& matches,
92  const lanelet::traffic_rules::TrafficRulesPtr& trafficRulesPtr) {
93  try {
94  return object(removeNonRuleCompliantMatchesImpl<ConstLaneletMatchProbabilistic>(matches, trafficRulesPtr));
95  } catch (const boost::python::error_already_set&) {
96  clearPythonErrors();
97  }
98  try {
99  return object(removeNonRuleCompliantMatchesImpl<ConstLaneletMatch>(matches, trafficRulesPtr));
100  } catch (const boost::python::error_already_set&) {
101  clearPythonErrors();
102  }
103  throw std::runtime_error("Matches must be a list of ConstLaneletMatch(es) or ConstLaneletMatch(es)Probabilistic");
104 }
105 
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);
110 }
111 
112 std::vector<ConstLaneletMatch> (*funcWrapperDeterministic)(const LaneletMap&, const Object2d&,
113  const double) = &getDeterministicMatches;
114 std::vector<ConstLaneletMatchProbabilistic> (*funcWrapperProbabilistic)(const LaneletMap&,
115  const ObjectWithCovariance2d&,
116  const double) = &getProbabilisticMatches;
117 } // namespace
119 
120 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
121  auto core = import("lanelet2.core");
122 
123  class_<Pose2d>("Pose2d", "2D Isometric Transformation", no_init)
124  .def("__init__",
125  make_constructor(&createPose, default_call_policies(), (arg("x") = 0., arg("y") = 0, arg("yaw") = 0.)))
126  .def("__str__", &printPoseWrapper);
127 
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)});
132  },
133  default_call_policies(),
134  (arg("objectId") = lanelet::InvalId, arg("pose") = Pose2d::Identity(),
135  arg("absoluteHull") = boost::python::list())))
136  .add_property(
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);
141 
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));
146 
147  class_<ObjectWithCovariance2d, bases<Object2d>>("ObjectWithCovariance2d", "Object with pose, covariance, hull and ID",
148  no_init)
149  .def("__init__", make_constructor(
150  +[](lanelet::Id objectId, const Pose2d& pose, const boost::python::list& absoluteHull,
151  const PositionCovariance2d& positionCovariance, double vonMisesKappa) {
153  obj.objectId = objectId;
154  obj.pose = pose;
155  obj.absoluteHull = hullFromList(absoluteHull);
156  obj.positionCovariance = positionCovariance;
157  obj.vonMisesKappa = vonMisesKappa;
158  return boost::make_shared<ObjectWithCovariance2d>(obj);
159  // initializer list construction of derived struct requires cpp17
160  // return boost::make_shared<ObjectWithCovariance2d>(ObjectWithCovariance2d{
161  // objectId, pose, hullFromList(absoluteHull), positionCovariance, vonMisesKappa});
162  },
163  default_call_policies(),
164  (arg("objectId") = lanelet::InvalId, arg("pose") = Pose2d::Identity(),
165  arg("absoluteHull") = boost::python::list(),
166  arg("positionCovariance") = PositionCovariance2d(), arg("vonMisesKappa") = 0.)))
167  .def_readwrite("vonMisesKappa", &ObjectWithCovariance2d::vonMisesKappa)
168  .def_readwrite("positionCovariance", &ObjectWithCovariance2d::positionCovariance);
169 
170  class_<ConstLaneletMatch>("ConstLaneletMatch", "Results from matching objects to lanelets", no_init)
171  .def_readwrite("lanelet", &ConstLaneletMatch::lanelet)
172  .def_readwrite("distance", &ConstLaneletMatch::distance);
173 
174  class_<ConstLaneletMatchProbabilistic, bases<ConstLaneletMatch>>("ConstLaneletMatchProbabilistic",
175  "Results from matching objects to lanelets", no_init)
176  .def_readwrite("mahalanobisDistSq", &ConstLaneletMatchProbabilistic::mahalanobisDistSq);
177 
178  VectorToListConverter<std::vector<ConstLaneletMatch>>();
179  VectorToListConverter<std::vector<ConstLaneletMatchProbabilistic>>();
180 
181  def("getDeterministicMatches", funcWrapperDeterministic);
182  def("getProbabilisticMatches", funcWrapperProbabilistic);
183  def("removeNonRuleCompliantMatches", ruleCheckWrapper);
184 }
lanelet::InvalId
constexpr Id InvalId
LaneletMap.h
lanelet
lanelet::matching::ObjectWithCovariance2d::vonMisesKappa
double vonMisesKappa
p
BasicPoint p
lanelet::Id
int64_t Id
LaneletMatching.h
Pose2d
Eigen::Transform< double, 2, Eigen::Isometry, Eigen::DontAlign > Pose2d
PositionCovariance2d
Eigen::Matrix< double, 2, 2, Eigen::DontAlign > PositionCovariance2d
converter.h
lanelet::LaneletMap
lanelet::matching::Object2d::pose
Pose2d pose
lanelet::matching::Object2d
lanelet::matching::Object2d::absoluteHull
Hull2d absoluteHull
lanelet::matching::Object2d::objectId
Id objectId
TrafficRules.h
converters::VectorToListConverter
py::to_python_converter< T, VectorToList< T > > VectorToListConverter
Definition: converter.h:219
lanelet::matching
Types.h
lanelet::matching::ObjectWithCovariance2d
lanelet::matching::ObjectWithCovariance2d::positionCovariance
PositionCovariance2d positionCovariance
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: matching.cpp:120
lanelet::BasicPolygon2d
lanelet::traffic_rules::TrafficRulesPtr
std::shared_ptr< TrafficRules > TrafficRulesPtr


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