core.cpp
Go to the documentation of this file.
6 #include <lanelet2_core/primitives/RegulatoryElement.h>
7 
8 #include <boost/python/object_core.hpp>
9 #include <boost/python/return_by_value.hpp>
10 #include <boost/python/return_internal_reference.hpp>
11 #include <sstream>
12 #include <stdexcept>
13 
15 #include "lanelet2_core/Forward.h"
16 #include "lanelet2_core/primitives/Area.h"
18 
19 using namespace boost::python;
20 using namespace lanelet;
21 
22 namespace {
23 void formatHelper(std::ostream& os) {}
24 
25 template <typename... Args>
26 // NOLINTNEXTLINE(readability-identifier-naming)
27 void formatHelper(std::ostream& os, const std::string& s, const Args&... Args_) {
28  if (!s.empty()) {
29  os << ", ";
30  }
31  os << s;
32  formatHelper(os, Args_...);
33 }
34 
35 template <typename T, typename... Args>
36 // NOLINTNEXTLINE(readability-identifier-naming)
37 void formatHelper(std::ostream& os, const T& next, const Args&... Args_) {
38  os << ", ";
39  os << next;
40  formatHelper(os, Args_...);
41 }
42 
43 template <typename T, typename... Args>
44 // NOLINTNEXTLINE(readability-identifier-naming)
45 void format(std::ostream& os, const T& first, const Args&... Args_) {
46  os << first;
47  formatHelper(os, Args_...);
48 }
49 
50 template <typename... Args>
51 // NOLINTNEXTLINE(readability-identifier-naming)
52 std::string makeRepr(const char* name, const Args&... Args_) {
53  std::ostringstream os;
54  os << name << '(';
55  format(os, Args_...);
56  os << ')';
57  return os.str();
58 }
59 
60 struct AttributeToPythonStr {
61  static PyObject* convert(Attribute const& s) { return boost::python::incref(boost::python::object(s.value()).ptr()); }
62 };
63 
64 struct AttributeFromPythonStr {
65  AttributeFromPythonStr() {
66  boost::python::converter::registry::push_back(&convertible, &construct, boost::python::type_id<Attribute>());
67  }
68 
69  static void* convertible(PyObject* objPtr) {
70 #if PY_MAJOR_VERSION < 3
71  return PyString_Check(objPtr) ? objPtr : nullptr; // NOLINT
72 #else
73  return PyUnicode_Check(objPtr) ? objPtr : nullptr; // NOLINT
74 #endif
75  }
76 
77  static void construct(PyObject* objPtr, boost::python::converter::rvalue_from_python_stage1_data* data) {
78 #if PY_MAJOR_VERSION < 3
79  const char* value = PyString_AsString(objPtr);
80 #else
81  auto* pyStr = PyUnicode_AsUTF8String(objPtr);
82  const char* value = PyBytes_AsString(pyStr);
83 #endif
84  if (value == nullptr) {
85  boost::python::throw_error_already_set();
86  }
87  using StorageType = boost::python::converter::rvalue_from_python_storage<Attribute>;
88  void* storage = reinterpret_cast<StorageType*>(data)->storage.bytes; // NOLINT
89  new (storage) Attribute(value);
90  data->convertible = storage;
91  }
92 };
93 
94 struct DictToAttributeMapConverter {
95  DictToAttributeMapConverter() { converter::registry::push_back(&convertible, &construct, type_id<AttributeMap>()); }
96  static void* convertible(PyObject* obj) {
97  if (!PyDict_CheckExact(obj)) { // NOLINT
98  return nullptr;
99  }
100  return obj;
101  }
102  static void construct(PyObject* obj, converter::rvalue_from_python_stage1_data* data) {
103  dict d(borrowed(obj));
104  list keys = d.keys();
105  list values = d.values();
106  AttributeMap attributes;
107  for (auto i = 0u; i < len(keys); ++i) {
108  std::string key = extract<std::string>(keys[i]);
109  std::string value = extract<std::string>(values[i]);
110  attributes.insert(std::make_pair(key, value));
111  }
112  using StorageType = converter::rvalue_from_python_storage<AttributeMap>;
113  void* storage = reinterpret_cast<StorageType*>(data)->storage.bytes; // NOLINT
114  new (storage) AttributeMap(attributes);
115  data->convertible = storage;
116  }
117 };
118 
119 struct LineStringOrPolygonToObject {
120  static PyObject* convert(const lanelet::LineStringOrPolygon3d& v) {
121  if (v.isPolygon()) {
122  return incref(object(*v.polygon()).ptr());
123  }
124  if (v.isLineString()) {
125  return incref(object(*v.lineString()).ptr());
126  }
127  return incref(object().ptr());
128  }
129 };
130 
131 struct ConstLineStringOrPolygonToObject {
132  static PyObject* convert(const lanelet::ConstLineStringOrPolygon3d& v) {
133  if (v.isPolygon()) {
134  return incref(object(*v.polygon()).ptr());
135  }
136  if (v.isLineString()) {
137  return incref(object(*v.lineString()).ptr());
138  }
139  return incref(object().ptr());
140  }
141 };
142 
143 struct ConstLaneletOrAreaToObject {
144  static PyObject* convert(const lanelet::ConstLaneletOrArea& v) {
145  if (v.isArea()) {
146  return incref(object(*v.area()).ptr());
147  }
148  if (v.isLanelet()) {
149  return incref(object(*v.lanelet()).ptr());
150  }
151  return incref(object().ptr());
152  }
153 };
154 
155 template <class T>
156 struct MapItem {
157  using K = typename T::key_type;
158  using V = typename T::mapped_type;
159  using Iter = typename T::const_iterator;
160 
161  MapItem& fromPython() {
162  &MapItem::convertible, &MapItem::init, boost::python::type_id<T>();
163  return *this;
164  }
165  static list keys(T const& x) {
166  list t;
167  for (auto it = x.begin(); it != x.end(); ++it) {
168  t.append(it->first);
169  }
170  return t;
171  }
172  static list values(T const& x) {
173  list t;
174  for (auto it = x.begin(); it != x.end(); ++it) {
175  t.append(it->second);
176  }
177  return t;
178  }
179  static list items(T const& x) {
180  list t;
181  for (auto it = x.begin(); it != x.end(); ++it) {
182  t.append(boost::python::make_tuple(it->first, it->second));
183  }
184  return t;
185  }
186  static void* convertible(PyObject* object) { return PyObject_GetIter(object) != nullptr ? object : nullptr; }
187  static std::shared_ptr<T> init(boost::python::dict& pyDict) {
188  auto mapPtr = std::make_shared<T>();
189  auto& map = *mapPtr;
190  boost::python::list keys = pyDict.keys();
191  for (int i = 0; i < len(keys); ++i) { // NOLINT
192  boost::python::extract<K> extractedKey(keys[i]);
193  if (!extractedKey.check()) {
194  PyErr_SetString(PyExc_KeyError, "Key invalid!");
195  throw_error_already_set();
196  }
197  K key = extractedKey;
198  boost::python::extract<V> extractedVal(pyDict[key]);
199  if (!extractedVal.check()) {
200  PyErr_SetString(PyExc_KeyError, "Value invalid!");
201  throw_error_already_set();
202  }
203  V value = extractedVal;
204  map[key] = value; // NOLINT
205  }
206  return mapPtr;
207  }
208 };
209 
210 template <typename T>
211 void setXWrapper(T& obj, double x) {
212  obj.x() = x;
213 }
214 template <typename T>
215 void setYWrapper(T& obj, double y) {
216  obj.y() = y;
217 }
218 
219 template <typename T>
220 void setZWrapper(T& obj, double z) {
221  obj.z() = z;
222 }
223 template <typename T>
224 double getXWrapper(const T& obj) {
225  return obj.x();
226 }
227 template <typename T>
228 double getYWrapper(const T& obj) {
229  return obj.y();
230 }
231 
232 template <typename T>
233 double getZWrapper(const T& obj) {
234  return obj.z();
235 }
236 
237 template <typename Func>
238 auto getRefFunc(Func&& f) {
239  return make_function(std::forward<Func>(f), return_internal_reference<>());
240 }
241 
242 template <typename T>
243 void setAttributeWrapper(T& obj, const AttributeMap& attr) {
244  obj.attributes() = attr;
245 }
246 
247 template <typename PrimT>
248 class IsPrimitive : public def_visitor<IsPrimitive<PrimT>> {
249  using ConstT = const PrimT;
250 
251  public:
252  template <typename ClassT>
253  void visit(ClassT& c) const {
254  const AttributeMap& (PrimT::*attr)() const = &PrimT::attributes;
255  c.add_property("id", &PrimT::id, &PrimT::setId,
256  "Unique ID of this primitive. 0 is a special value for temporary objects.");
257  c.add_property("attributes", getRefFunc(attr), setAttributeWrapper<PrimT>,
258  "The attributes of this primitive as key value types. Behaves like a dictionary.");
259  c.def(self == self); // NOLINT
260  c.def(self != self); // NOLINT
261  c.def(self_ns::str(self_ns::self));
262  c.def(
263  "__hash__", +[](const PrimT& self) { return std::hash<PrimT>()(self); });
264  }
265 };
266 
267 template <typename PrimT>
268 class IsConstPrimitive : public def_visitor<IsConstPrimitive<PrimT>> {
269  friend class def_visitor_access;
270 
271  public:
272  template <typename ClassT>
273  void visit(ClassT& c) const {
274  c.add_property("id", &PrimT::id, "Unique ID of this primitive. 0 is a special value for temporary objects.");
275  const AttributeMap& (PrimT::*attr)() const = &PrimT::attributes;
276  c.add_property("attributes", getRefFunc(attr),
277  "The attributes of this primitive as key value types. Behaves like a dictionary.");
278  c.def(self == self); // NOLINT
279  c.def(self != self); // NOLINT
280  c.def(self_ns::str(self_ns::self));
281  c.def(
282  "__hash__", +[](const PrimT& self) { return std::hash<PrimT>()(self); });
283  }
284 };
285 
286 template <typename LsT, bool InternalRef = true>
287 class IsConstLineString : public def_visitor<IsConstLineString<LsT, InternalRef>> {
288  friend class def_visitor_access;
289 
290  public:
291  template <typename ClassT>
292  void visit(ClassT& c) const {
293  c.def("__iter__", iterator<LsT>())
294  .def("__len__", &LsT::size, "Number of points in this linestring")
295  .def("__iter__", iterator<LsT>())
296  .def("inverted", &LsT::inverted, "Returns whether this is an inverted linestring");
297  addGetitem<InternalRef>(c);
298  }
299  template <bool InternalRefVal, typename ClassT>
300  std::enable_if_t<InternalRefVal> addGetitem(ClassT& c) const {
301  c.def("__getitem__", wrappers::getItem<LsT>, return_internal_reference<>());
302  }
303  template <bool InternalRefVal, typename ClassT>
304  std::enable_if_t<!InternalRefVal> addGetitem(ClassT& c) const {
305  c.def("__getitem__", wrappers::getItem<LsT>, return_value_policy<return_by_value>());
306  }
307 
308  private:
309  bool internalRef_{false};
310 };
311 
312 template <typename LsT>
313 class IsLineString : public def_visitor<IsLineString<LsT>> {
314  friend class def_visitor_access;
315 
316  public:
317  template <typename ClassT>
318  void visit(ClassT& c) const {
319  c.def("__setitem__", wrappers::setItem<LsT, typename LsT::PointType>)
320  .def("__delitem__", wrappers::delItem<LsT>)
321  .def("append", &LsT::push_back, "Appends a new point at the end of this linestring", arg("point"))
322  .def("__iter__", iterator<LsT>())
323  .def("__len__", &LsT::size, "Number of points in this linestring")
324  .def("inverted", &LsT::inverted, "Returns whether this is an inverted linestring");
325  addGetitem(c);
326  }
327  template <typename ClassT>
328  void addGetitem(ClassT& c) const {
329  c.def("__getitem__", wrappers::getItem<LsT>, return_internal_reference<>());
330  }
331 };
332 
333 template <typename T>
334 class IsHybridMap : public def_visitor<IsHybridMap<T>> {
335  friend class def_visitor_access;
336 
337  public:
338  template <typename ClassT>
339  void visit(ClassT& c) const {
340  c.def("__init__", make_constructor(MapItem<T>::init))
341  .def(map_indexing_suite<T, true>())
342  .def("keys", MapItem<T>::keys)
343  .def("values", MapItem<T>::values)
344  .def("items", MapItem<T>::items, "Iterates over the key-value pairs")
345  .def(self == self) // NOLINT
346  .def(self != self); // NOLINT
347  }
348 };
349 
350 template <typename T>
351 T addWrapper(const T& rhs, const T& lhs) {
352  return (rhs + lhs);
353 }
354 
355 template <typename T>
356 T subWrapper(const T& rhs, const T& lhs) {
357  return (rhs - lhs);
358 }
359 
360 template <typename T1, typename T2>
361 T1 mulWrapper(const T1& rhs, const T2& lhs) {
362  return (rhs * lhs).eval();
363 }
364 
365 template <typename T1, typename T2>
366 T2 rmulWrapper(const T1& rhs, const T2& lhs) {
367  return (rhs * lhs).eval();
368 }
369 
370 template <typename T1, typename T2>
371 T1 divWrapper(const T1& rhs, const T2& lhs) {
372  return (rhs / lhs).eval();
373 }
374 
375 template <typename T>
376 using SetAttrSig = void (T::*)(const std::string&, const Attribute&);
377 
378 template <typename T>
379 using GetAttrSig = const Attribute& (ConstPrimitive<T>::*)(const std::string&) const;
380 
381 template <typename LayerT = PointLayer, typename... ClassArgs>
382 auto wrapLayer(const char* layerName) {
383  auto get = static_cast<typename LayerT::PrimitiveT (LayerT::*)(Id)>(&LayerT::get);
384  auto search = static_cast<typename LayerT::PrimitiveVec (LayerT::*)(const BoundingBox2d&)>(&LayerT::search);
385  auto nearest =
386  static_cast<typename LayerT::PrimitiveVec (LayerT::*)(const BasicPoint2d&, unsigned)>(&LayerT::nearest);
387  return class_<LayerT, boost::noncopyable, ClassArgs...>(layerName,
388  "Primitive layer in a LaneletMap and LaneletSubmap", no_init)
389  .def("exists", &LayerT::exists, arg("id"), "Check if a primitive ID exists")
390  .def("__contains__", &LayerT::exists, arg("id"), "Check if a primitive ID exists")
391  .def(
392  "__contains__",
393  +[](LayerT& self, const typename LayerT::PrimitiveT& elem) { return self.exists(utils::getId(elem)); },
394  arg("elem"), "Check if a primitive with this ID exists")
395  .def("get", get, arg("id"), "Get a primitive with this ID")
396  .def("__iter__", iterator<LayerT>(), "Iterate primitives in this layer in arbitrary order")
397  .def("__len__", &LayerT::size, "Number of items in this layer")
398  .def(
399  "__getitem__", +[](LayerT& self, Id idx) { return self.get(idx); }, arg("id"),
400  "Retrieve an element by its ID")
401  .def("search", search, arg("boundingBox"), "Search in a search area defined by a 2D bounding box")
402  .def("nearest", nearest, (arg("point"), arg("n") = 1), "Gets a list of the nearest n primitives to a given point")
403  .def("uniqueId", &LayerT::uniqueId, "Retrieve an ID that not yet used in this layer");
404 }
405 
406 template <typename PrimT>
407 auto selectAdd() {
408  return static_cast<void (LaneletMap::*)(PrimT)>(&LaneletMap::add);
409 }
410 template <typename PrimT>
411 auto selectSubmapAdd() {
412  return static_cast<void (LaneletSubmap::*)(PrimT)>(&LaneletSubmap::add);
413 }
414 
415 template <typename RegelemT>
416 std::vector<std::shared_ptr<RegelemT>> regelemAs(Lanelet& llt) {
417  return llt.regulatoryElementsAs<RegelemT>();
418 }
419 
420 template <typename RegelemT>
421 std::vector<std::shared_ptr<RegelemT>> constRegelemAs(ConstLanelet& llt) {
422  return utils::transform(llt.regulatoryElementsAs<RegelemT>(),
423  [](auto& e) { return std::const_pointer_cast<RegelemT>(e); });
424 }
425 
426 template <typename PrimT>
427 LaneletMapPtr createMapWrapper(const PrimT& prim) {
428  return utils::createMap(prim);
429 }
430 
431 template <typename PrimT>
432 LaneletSubmapPtr createSubmapWrapper(const PrimT& prim) {
433  return utils::createSubmap(prim);
434 }
435 
436 template <typename T>
437 object optionalToObject(const Optional<T>& v) {
438  return v ? object(*v) : object();
439 }
440 
441 template <typename T>
442 Optional<T> objectToOptional(const object& o) {
443  return o == object() ? Optional<T>{} : Optional<T>{extract<T>(o)()};
444 }
445 
446 std::string repr(const object& o) {
447  object repr = import("builtins").attr("repr");
448  return call<std::string>(repr.ptr(), o);
449 }
450 
451 std::string repr(const AttributeMap& a) {
452  if (a.empty()) {
453  return {};
454  }
455  return repr(object(a));
456 }
457 
458 std::string repr(const RegulatoryElementConstPtrs& regelems) {
459  if (regelems.empty()) {
460  return {};
461  }
462  return repr(list(regelems));
463 }
464 } // namespace
465 
466 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
467  class_<BasicPoint2d>("BasicPoint2d", "A simple 2D point", init<double, double>((arg("x") = 0., arg("y") = 0.)))
468  .def(init<>("BasicPoint2d()"))
469  .add_property("x", getXWrapper<BasicPoint2d>, setXWrapper<BasicPoint2d>, "x coordinate")
470  .add_property("y", getYWrapper<BasicPoint2d>, setYWrapper<BasicPoint2d>, "y coordinate")
471  .def("__add__", addWrapper<BasicPoint2d>)
472  .def("__sub__", subWrapper<BasicPoint2d>)
473  .def("__mul__", mulWrapper<BasicPoint2d, double>)
474  .def("__rmul__", mulWrapper<BasicPoint2d, double>)
475  .def("__div__", divWrapper<BasicPoint2d, double>)
476  .def(
477  "__repr__", +[](BasicPoint2d p) { return makeRepr("BasicPoint2d", p.x(), p.y()); })
478  .def(self_ns::str(self_ns::self));
479 
480  class_<Eigen::Vector2d>("Vector2d", "A simple point", no_init)
481  .add_property("x", getXWrapper<BasicPoint2d>, setXWrapper<BasicPoint2d>, "x coordinate")
482  .add_property("y", getYWrapper<BasicPoint2d>, setYWrapper<BasicPoint2d>, "y coordinate")
483  .def("__add__", addWrapper<BasicPoint2d>)
484  .def("__sub__", subWrapper<BasicPoint2d>)
485  .def("__mul__", mulWrapper<BasicPoint2d, double>)
486  .def("__rmul__", mulWrapper<BasicPoint2d, double>)
487  .def("__div__", divWrapper<BasicPoint2d, double>)
488  .def(
489  "__repr__", +[](Eigen::Vector2d p) { return makeRepr("Vector2d", p.x(), p.y()); })
490  .def(self_ns::str(self_ns::self));
491 
492  implicitly_convertible<Eigen::Vector2d, BasicPoint2d>();
493 
494  class_<BasicPoint3d>("BasicPoint3d", "A simple point",
495  init<double, double, double>((arg("x") = 0., arg("y") = 0., arg("z") = 0.)))
496  .add_property("x", getXWrapper<BasicPoint3d>, setXWrapper<BasicPoint3d>, "x coordinate")
497  .add_property("y", getYWrapper<BasicPoint3d>, setYWrapper<BasicPoint3d>, "y coordinate")
498  .add_property("z", getZWrapper<BasicPoint3d>, setZWrapper<BasicPoint3d>, "z coordinate")
499  .def("__add__", addWrapper<BasicPoint3d>)
500  .def("__sub__", subWrapper<BasicPoint3d>)
501  .def("__mul__", mulWrapper<BasicPoint3d, double>)
502  .def("__rmul__", mulWrapper<BasicPoint3d, double>)
503  .def("__div__", divWrapper<BasicPoint3d, double>)
504  .def(
505  "__repr__", +[](BasicPoint3d p) { return makeRepr("BasicPoint3d", p.x(), p.y(), p.z()); })
506  .def(self_ns::str(self_ns::self));
507 
508  class_<BoundingBox2d>("BoundingBox2d",
509  init<BasicPoint2d, BasicPoint2d>(
510  (arg("min"), arg("max")),
511  "Initialize box with its minimum point (lower left) and its maximum (upper right) corner"))
512  .add_property(
513  "min",
514  make_function(
515  +[](BoundingBox2d& self) -> BasicPoint2d& { return self.min(); }, return_internal_reference<>()),
516  +[](BoundingBox2d& self, const BasicPoint2d& p) { self.min() = p; }, "Minimum corner (lower left)")
517  .add_property(
518  "max",
519  make_function(
520  +[](BoundingBox2d& self) -> BasicPoint2d& { return self.max(); }, return_internal_reference<>()),
521  +[](BoundingBox2d& self, const BasicPoint2d& p) { self.max() = p; }, "Maximum corner (upper right)")
522  .def(
523  "__repr__", +[](BoundingBox2d box) {
524  return makeRepr("BoundingBox2d", repr(object(box.min())), repr(object(box.max())));
525  });
526 
527  class_<BoundingBox3d>("BoundingBox3d",
528  init<BasicPoint3d, BasicPoint3d>(
529  (arg("min"), arg("max")),
530  "Initialize box with its minimum (lower laft) and its maximum (upper right) corner"))
531  .add_property(
532  "min",
533  make_function(
534  +[](BoundingBox3d& self) -> BasicPoint3d& { return self.min(); }, return_internal_reference<>{}),
535  +[](BoundingBox3d& self, const BasicPoint3d& p) { self.min() = p; }, "Minimum corner")
536  .add_property(
537  "max",
538  make_function(
539  +[](BoundingBox3d& self) -> BasicPoint3d& { return self.max(); }, return_internal_reference<>{}),
540  +[](BoundingBox3d& self, const BasicPoint3d& p) { self.max() = p; }, "Maximum corner")
541  .def(
542  "__repr__", +[](const BoundingBox3d& box) {
543  return makeRepr("BoundingBox3d", repr(object(box.min())), repr(object(box.max())));
544  });
545 
546  boost::python::to_python_converter<Attribute, AttributeToPythonStr>();
547 
548  using ::converters::IterableConverter;
551  using ::converters::ToOptionalConverter;
555 
556  VariantConverter<RuleParameter>();
557  VariantConverter<ConstRuleParameter>();
558 
559  VectorToListConverter<Points3d>();
560  VectorToListConverter<Points2d>();
561  VectorToListConverter<BasicPoints3d>();
562  VectorToListConverter<std::vector<BasicPoint2d>>();
563  VectorToListConverter<ConstPoints3d>();
564  VectorToListConverter<ConstPoints2d>();
565  VectorToListConverter<LineStrings3d>();
566  VectorToListConverter<LineStrings2d>();
567  VectorToListConverter<ConstLineStrings3d>();
568  VectorToListConverter<ConstLineStrings2d>();
569  VectorToListConverter<BasicPolygon3d>();
570  VectorToListConverter<BasicPolygon2d>();
571  VectorToListConverter<Polygons3d>();
572  VectorToListConverter<Polygons2d>();
573  VectorToListConverter<ConstPolygons3d>();
574  VectorToListConverter<ConstPolygons2d>();
575  VectorToListConverter<CompoundPolygons3d>();
576  VectorToListConverter<CompoundPolygons2d>();
577  VectorToListConverter<Lanelets>();
578  VectorToListConverter<ConstLanelets>();
579  VectorToListConverter<LaneletSequences>();
580  VectorToListConverter<LaneletsWithStopLines>();
581  VectorToListConverter<RuleParameters>();
582  VectorToListConverter<ConstRuleParameters>();
583  VectorToListConverter<RegulatoryElementPtrs>();
584  VectorToListConverter<RegulatoryElementConstPtrs>();
585  VectorToListConverter<LineStringsOrPolygons3d>();
586  VectorToListConverter<ConstLineStringsOrPolygons3d>();
587  VectorToListConverter<ConstLaneletOrAreas>();
588  VectorToListConverter<Areas>();
589  VectorToListConverter<std::vector<TrafficLight::Ptr>>();
590  VectorToListConverter<std::vector<TrafficSign::Ptr>>();
591  VectorToListConverter<std::vector<SpeedLimit::Ptr>>();
592  VectorToListConverter<std::vector<RightOfWay::Ptr>>();
593  VectorToListConverter<std::vector<AllWayStop::Ptr>>();
594  VectorToListConverter<std::vector<std::shared_ptr<const TrafficLight>>>();
595  VectorToListConverter<std::vector<std::shared_ptr<const TrafficSign>>>();
596  VectorToListConverter<std::vector<std::shared_ptr<const SpeedLimit>>>();
597  VectorToListConverter<std::vector<std::shared_ptr<const RightOfWay>>>();
598  VectorToListConverter<std::vector<std::shared_ptr<const AllWayStop>>>();
599  VectorToListConverter<std::vector<std::string>>();
600  VectorToListConverter<Ids>();
601  AttributeFromPythonStr();
602  DictToAttributeMapConverter();
603 
604  OptionalConverter<Point2d>();
605  OptionalConverter<Point3d>();
606  OptionalConverter<ConstPoint2d>();
607  OptionalConverter<ConstPoint3d>();
608  OptionalConverter<LineString3d>();
609  OptionalConverter<LineString2d>();
610  OptionalConverter<ConstLineString3d>();
611  OptionalConverter<ConstLineString2d>();
612  OptionalConverter<LineStrings3d>();
613  OptionalConverter<LineStrings2d>();
614  OptionalConverter<ConstLineStrings3d>();
615  OptionalConverter<ConstLineStrings2d>();
616  OptionalConverter<LineStringsOrPolygons3d>();
617  OptionalConverter<Lanelet>();
618  OptionalConverter<ConstLanelet>();
619  OptionalConverter<LaneletSequence>();
620  OptionalConverter<Area>();
621  OptionalConverter<ConstArea>();
622  OptionalConverter<Polygon2d>();
623  OptionalConverter<Polygon3d>();
624  OptionalConverter<ConstPolygon2d>();
625  OptionalConverter<ConstPolygon3d>();
626  OptionalConverter<RuleParameter>();
627  OptionalConverter<ConstRuleParameter>();
628  OptionalConverter<RegulatoryElement>();
629 
630  PairConverter<std::pair<BasicPoint2d, BasicPoint2d>>();
631  PairConverter<std::pair<BasicPoint3d, BasicPoint3d>>();
632 
633  WeakConverter<WeakLanelet>();
634  WeakConverter<WeakArea>();
635 
636  // Register interable conversions.
637  IterableConverter()
638  .fromPython<Points3d>()
639  .fromPython<Points2d>()
640  .fromPython<ConstLineStrings3d>()
641  .fromPython<ConstLineStrings2d>()
642  .fromPython<LineStrings3d>()
643  .fromPython<LineStrings2d>()
644  .fromPython<Polygons2d>()
645  .fromPython<Polygons3d>()
646  .fromPython<InnerBounds>()
647  .fromPython<Lanelets>()
648  .fromPython<ConstLanelets>()
649  .fromPython<LaneletsWithStopLines>()
650  .fromPython<Areas>()
651  .fromPython<ConstAreas>()
652  .fromPython<RegulatoryElementPtrs>()
653  .fromPython<LineStringsOrPolygons3d>()
654  .fromPython<ConstLineStringsOrPolygons3d>();
655 
656  ToOptionalConverter().fromPython<LineString3d>();
657 
658  to_python_converter<LineStringOrPolygon3d, LineStringOrPolygonToObject>();
659  to_python_converter<ConstLineStringOrPolygon3d, ConstLineStringOrPolygonToObject>();
660  to_python_converter<ConstLaneletOrArea, ConstLaneletOrAreaToObject>();
661  implicitly_convertible<LineString3d, LineStringOrPolygon3d>();
662  implicitly_convertible<Polygon3d, LineStringOrPolygon3d>();
663  implicitly_convertible<ConstLineString3d, ConstLineStringOrPolygon3d>();
664  implicitly_convertible<ConstPolygon3d, ConstLineStringOrPolygon3d>();
665  implicitly_convertible<ConstLanelet, ConstLaneletOrArea>();
666  implicitly_convertible<ConstArea, ConstLaneletOrArea>();
667 
668  class_<AttributeMap>("AttributeMap", "Stores attributes as key-value pairs. Behaves similar to a dict.",
669  init<>("Create an empty attriute map"))
670  .def(IsHybridMap<AttributeMap>())
671  .def(self_ns::str(self_ns::self))
672  .def(
673  "__repr__", +[](const AttributeMap& a) { return makeRepr("AttributeMap", repr(dict(a))); });
674 
675  class_<RuleParameterMap>("RuleParameterMap",
676  "Used by RegulatoryElement. Works like a dictionary that maps roles (strings) to a list of "
677  "primitives with that role (parameters).",
678  init<>("Create empty rule parameter map"))
679  .def(IsHybridMap<RuleParameterMap>())
680  .def(
681  "__repr__", +[](const RuleParameterMap& r) { return makeRepr("RuleParameterMap", repr(dict(r))); });
682 
683  class_<ConstRuleParameterMap>("ConstRuleParameterMap", init<>("ConstRuleParameterMap()"))
684  .def(IsHybridMap<ConstRuleParameterMap>())
685  .def(
686  "__repr__", +[](const RuleParameterMap& r) { return makeRepr("RuleParameterMap", repr(dict(r))); });
687 
688  class_<ConstPoint2d>("ConstPoint2d",
689  "Immutable 2D point primitive. It can not be instanciated from python but is returned from a "
690  "few lanelet2 algorithms",
691  no_init)
692  .def(IsConstPrimitive<ConstPoint2d>())
693  .add_property("x", getXWrapper<ConstPoint2d>, "x coordinate")
694  .add_property("y", getYWrapper<ConstPoint2d>, "y coordinate")
695  .def("basicPoint", &ConstPoint2d::basicPoint, return_internal_reference<>(),
696  "Returns a plain 2D point primitive (no ID, no attributes) for efficient geometry operations");
697  class_<Point2d, bases<ConstPoint2d>>(
698  "Point2d",
699  "Lanelet's 2D point primitive. Directly convertible to a 3D point, because it is just a 2D view on the "
700  "existing 3D data. Use lanelet2.geometry.to3D for this.",
701  init<Id, BasicPoint3d, AttributeMap>((arg("id"), arg("point"), arg("attributes") = AttributeMap())))
702  .def(init<>("Point2d()"))
703  .def(init<Point3d>("Point3d()"))
704  .def(init<Id, double, double, double, AttributeMap>(
705  (arg("id"), arg("x"), arg("y"), arg("z") = 0., arg("attributes") = AttributeMap())))
706  .add_property("x", getXWrapper<Point2d>, setXWrapper<Point2d>, "x coordinate")
707  .add_property("y", getYWrapper<Point2d>, setYWrapper<Point2d>, "y coordinate")
708  .def(
709  "__repr__", +[](const Point2d& p) { return makeRepr("Point2d", p.id(), p.x(), p.y(), repr(p.attributes())); })
710  .def(IsPrimitive<Point2d>());
711 
712  class_<ConstPoint3d>("ConstPoint3d",
713  "Immutable 3D point primitive. It can not be instanciated from python but is returned from a "
714  "few lanelet2 algorithms",
715  no_init)
716  .def(IsConstPrimitive<ConstPoint3d>())
717  .add_property("x", getXWrapper<ConstPoint3d>, "x coordinate")
718  .add_property("y", getYWrapper<ConstPoint3d>, "y coordinate")
719  .add_property("z", getZWrapper<ConstPoint3d>, "z coordinate")
720  .def(
721  "__repr__",
722  +[](const ConstPoint3d& p) {
723  return makeRepr("ConstPoint3d", p.id(), p.x(), p.y(), p.z(), repr(p.attributes()));
724  })
725  .def("basicPoint", &ConstPoint3d::basicPoint, return_internal_reference<>(),
726  "Returns a plain 3D point primitive (no ID, no attributes) for efficient geometry operations");
727 
728  class_<Point3d, bases<ConstPoint3d>>(
729  "Point3d",
730  "Lanelets 3D point primitive. Directly convertible to a 2D point, which shares the same view on the data. Use "
731  "lanelet2.geometry.to2D for this.",
732  init<Id, BasicPoint3d, AttributeMap>((arg("id"), arg("point"), arg("attributes") = AttributeMap())))
733  .def(init<>("Create a 3D point with ID 0 (invalid ID) at the origin"))
734  .def(init<Point2d>("Create a 3D point from a 2D point"))
735  .def(init<Id, double, double, double, AttributeMap>(
736  (arg("id"), arg("x"), arg("y"), arg("z") = 0., arg("attributes") = AttributeMap())))
737  .add_property("x", getXWrapper<Point3d>, setXWrapper<Point3d>, "x coordinate")
738  .add_property("y", getYWrapper<Point3d>, setYWrapper<Point3d>, "y coordinate")
739  .add_property("z", getZWrapper<Point3d>, setZWrapper<Point3d>, "z coordinate")
740  .def(
741  "__repr__",
742  +[](const Point3d& p) { return makeRepr("Point3d", p.id(), p.x(), p.y(), p.z(), repr(p.attributes())); })
743  .def(IsPrimitive<Point3d>());
744 
745  class_<GPSPoint, std::shared_ptr<GPSPoint>>("GPSPoint", "A raw GPS point", no_init)
746  .def("__init__", make_constructor(
747  // NOLINTNEXTLINE(bugprone-easily-swappable-parameters)
748  +[](double lat, double lon, double alt) {
749  return std::make_shared<GPSPoint>(GPSPoint({lat, lon, alt}));
750  },
751  default_call_policies(), (arg("lat") = 0., arg("lon") = 0., arg("ele") = 0)))
752  .def_readwrite("lat", &GPSPoint::lat, "Latitude according to WGS84")
753  .def_readwrite("lon", &GPSPoint::lon, "Longitude according to WGS84")
754  .def_readwrite("alt", &GPSPoint::ele, "DEPRECATED: Elevation according to WGS84 [m]. Use ele instead.")
755  .def_readwrite("ele", &GPSPoint::ele, "Elevation according to WGS84 [m]")
756  .def(
757  "__repr__", +[](const GPSPoint& p) { return makeRepr("GPSPoint", p.lat, p.lon, p.ele); });
758 
759  class_<ConstLineString2d>(
760  "ConstLineString2d",
761  "Immutable 2d lineString primitive. Behaves similar to a list of points. They cannot be created directly, but "
762  "are returned by some lanelet2 functions. Create mutable Linestring3d instead.",
763  init<ConstLineString3d>("Create (immutable) 2D Linestring from 3D linestring", (args("linestring"))))
764  .def("invert", &ConstLineString2d::invert,
765  "Creates a new, inverted linestring from this. This is essentially a view on the existing data, with points "
766  "returned in reversed order")
767  .def(IsConstLineString<ConstLineString2d>())
768  .def(IsConstPrimitive<ConstLineString2d>())
769  .def(
770  "__repr__", +[](const ConstLineString2d& ls) {
771  return makeRepr("ConstLineString2d", ls.id(), repr(list(ls)), repr(ls.attributes()));
772  });
773 
774  class_<LineString2d, bases<ConstLineString2d>>(
775  "LineString2d",
776  "Lanelet2s 2D linestring primitive. Has an ID, attributes and points with linear iterpolation in between the "
777  "points. Easily convertible to a 3D linestring, "
778  "because it is essentially a view on "
779  "the same 3D data. Use lanelet2.geometry.to3D for this.",
780  init<Id, Points3d, AttributeMap>("Create a linestring from an ID, a list of 3D points and attributes",
781  (arg("id"), arg("points"), arg("attributes"))))
782  .def(init<Id, Points3d>("Create a linestring from an ID and a list of 3D points", (arg("id"), arg("points"))))
783  .def(init<LineString3d>("Returns a 3D linestring for the current data. Both share the same data, modifications "
784  "affect both linestrings."))
785  .def("invert", &LineString2d::invert,
786  "Creates a new, inverted linestring from this. This is essentially a view on the existing data, with "
787  "points "
788  "returned in reversed order")
789  .def(
790  "__repr__",
791  +[](const ConstLineString3d& ls) {
792  return makeRepr("LineString3d", ls.id(), repr(list(ls)), repr(ls.attributes()));
793  })
794  .def(IsLineString<LineString2d>());
795 
796  class_<ConstLineString3d>("ConstLineString3d",
797  "Immutable 3d lineString primitive. They cannot be created directly, but "
798  "are returned by some lanelet2 functions. Create mutable Linestring3d instead. Use "
799  "lanelet2.geometry.to2D to convert to 2D pendant.",
800  init<ConstLineString2d>("Convert 2d linestring to 3D linestring"))
801  .def(init<Id, Points3d, AttributeMap>((arg("id"), arg("points"), arg("attributes") = AttributeMap())))
802  .def("invert", &ConstLineString3d::invert,
803  "Creates a new, inverted linestring from this. This is essentially a view on the existing data, with "
804  "points "
805  "returned in reversed order")
806  .def(
807  "__repr__",
808  +[](const ConstLineString3d& ls) {
809  return makeRepr("ConstLineString3d", ls.id(), repr(list(ls)), repr(ls.attributes()));
810  })
811  .def(IsConstLineString<ConstLineString3d>())
812  .def(IsConstPrimitive<ConstLineString3d>());
813 
814  class_<LineString3d, bases<ConstLineString3d>>(
815  "LineString3d",
816  "Lanelet's 3d lineString primitive. Has an ID, attribtues and points. Accessing individual points works similar "
817  "to python lists. Create mutable Linestring3d instead. Use lanelet2.geometry.to2D to convert to Linestring2d."
818  "convert to Linestring2d.",
819  init<Id, Points3d, AttributeMap>((arg("id") = 0, arg("points") = Points3d{}, arg("attributes") = AttributeMap())))
820  .def(init<LineString2d>(arg("linestring"),
821  "Converts a 2D linestring to a 3D linestring, sharing the same underlying data."))
822  .def("invert", &LineString3d::invert,
823  "Creates a new, inverted linestring from this. This is essentially a view on the existing data, with "
824  "points returned in reversed order")
825  .def(
826  "__repr__",
827  +[](const LineString3d& ls) {
828  return makeRepr("LineString3d", ls.id(), repr(list(ls)), repr(ls.attributes()));
829  })
830  .def(IsLineString<LineString3d>())
831  .def(IsPrimitive<LineString3d>());
832 
833  class_<ConstHybridLineString2d>(
834  "ConstHybridLineString2d",
835  "A 2D Linestring that behaves like a normal BasicLineString (i.e. returns BasicPoints), "
836  "but still has an ID and attributes.",
837  init<ConstLineString2d>(arg("linestring"), "Create from a 2D linestring"))
838  .def("invert", &ConstHybridLineString2d::invert,
839  "Creates a new, inverted linestring from this. This is essentially a view on the existing data, with "
840  "points returned in reversed order")
841  .def(
842  "__repr__",
843  +[](const ConstHybridLineString2d& ls) {
844  return makeRepr("ConstHybridLineString2d", ls.id(), repr(list(ls)), repr(ls.attributes()));
845  })
846  .def(IsConstLineString<ConstHybridLineString2d, false>())
847  .def(IsConstPrimitive<ConstHybridLineString2d>());
848 
849  class_<ConstHybridLineString3d>(
850  "ConstHybridLineString3d",
851  "A 3D Linestring that behaves like a normal BasicLineString (i.e. returns BasicPoints), "
852  "but still has an ID and attributes.",
853  init<ConstLineString3d>(arg("linestring"), "Create from a 3D linestring"))
854  .def("invert", &ConstHybridLineString3d::invert,
855  "Creates a new, inverted linestring from this. This is essentially a view on the existing data, with "
856  "points returned in reversed order")
857  .def(
858  "__repr__",
859  +[](const ConstHybridLineString3d& ls) {
860  return makeRepr("ConstHybridLineString3d", ls.id(), repr(list(ls)), repr(ls.attributes()));
861  })
862  .def(IsConstLineString<ConstHybridLineString3d, false>())
863  .def(IsConstPrimitive<ConstHybridLineString3d>());
864 
865  class_<CompoundLineString2d>("CompoundLineString2d",
866  "A LineString composed of multiple linestrings (i.e. it provides access to the points "
867  "in these linestrings in order)",
868  init<ConstLineStrings2d>(arg("linestrings"), "Create from a list of LineString2d"))
869  .def(IsConstLineString<CompoundLineString2d>())
870  .def("lineStrings", &CompoundLineString2d::lineStrings, "The linestrings that this linestring consists of")
871  .def("ids", &CompoundLineString2d::ids, "List of the IDs of the linestrings");
872 
873  class_<CompoundLineString3d>("CompoundLineString3d", "A LineString composed of multiple linestrings",
874  init<ConstLineStrings3d>(arg("linestrings"), "Create from a list of LineString3d"))
875  .def(IsConstLineString<CompoundLineString3d>())
876  .def("lineStrings", &CompoundLineString3d::lineStrings, "The linestrings that this linestring consists of")
877  .def("ids", &CompoundLineString3d::ids, "List of the IDs of the linestrings");
878 
879  class_<ConstPolygon2d>(
880  "ConstPolygon2d", "A two-dimensional lanelet polygon",
881  init<Id, Points3d, AttributeMap>((arg("id"), arg("points"), arg("attributes") = AttributeMap()),
882  "Create from an ID, a list of points and optionally attributes"))
883  .def(IsConstLineString<ConstPolygon2d>())
884  .def(
885  "__repr__",
886  +[](const ConstPolygon2d& p) {
887  return makeRepr("ConstPolygon2d", p.id(), repr(list(p)), repr(p.attributes()));
888  })
889  .def(IsConstPrimitive<ConstPolygon2d>());
890 
891  class_<ConstPolygon3d>(
892  "ConstPolygon3d", "A three-dimensional lanelet polygon",
893  init<Id, Points3d, AttributeMap>((arg("id"), arg("points"), arg("attributes") = AttributeMap())))
894  .def(
895  "__repr__",
896  +[](const ConstPolygon3d& p) {
897  return makeRepr("ConstPolygon3d", p.id(), repr(list(p)), repr(p.attributes()));
898  })
899  .def(IsConstLineString<ConstPolygon3d>())
900  .def(IsConstPrimitive<ConstPolygon3d>());
901 
902  class_<Polygon2d, bases<ConstPolygon2d>>(
903  "Polygon2d",
904  "A two-dimensional lanelet polygon. Points in clockwise order and open (i.e. start point != end point).",
905  init<Id, Points3d, AttributeMap>((arg("id"), arg("points"), arg("attributes") = AttributeMap()),
906  "Create from an ID, the boundary points and (optionally) attributes"))
907  .def(
908  "__repr__",
909  +[](const Polygon2d& p) { return makeRepr("Polygon2d", p.id(), repr(list(p)), repr(p.attributes())); })
910  .def(IsLineString<Polygon2d>())
911  .def(IsPrimitive<Polygon2d>());
912 
913  class_<Polygon3d, bases<ConstPolygon3d>>(
914  "Polygon3d",
915  "A two-dimensional lanelet polygon. Points in clockwise order and open (i.e. start point != end point).",
916  init<Id, Points3d, AttributeMap>((arg("id"), arg("points"), arg("attributes") = AttributeMap())))
917  .def(
918  "__repr__",
919  +[](const Polygon3d& p) { return makeRepr("Polygon3d", p.id(), repr(list(p)), repr(p.attributes())); })
920  .def(IsLineString<Polygon3d>())
921  .def(IsPrimitive<Polygon3d>());
922 
923  class_<CompoundPolygon2d>(
924  "CompoundPolygon2d", "A 2D polygon composed of multiple linestrings",
925  init<ConstLineStrings2d>(arg("linestrings"),
926  "Create a compound polygon from a list of linestrings (in clockwise order)"))
927  .def(IsConstLineString<CompoundPolygon2d>())
928  .def("lineStrings", &CompoundPolygon2d::lineStrings, "The linestrings in this polygon")
929  .def("ids", &CompoundPolygon2d::ids, "List of the ids of the linestrings");
930 
931  class_<CompoundPolygon3d>("CompoundPolygon3d", "A 3D polygon composed of multiple linestrings",
932  init<ConstLineStrings3d>())
933  .def(IsConstLineString<CompoundPolygon3d>())
934  .def("lineStrings", &CompoundPolygon3d::lineStrings, "The linestrings in this polygon")
935  .def("ids", &CompoundPolygon3d::ids, "List of the ids of the linestrings");
936 
937  class_<ConstLanelet>(
938  "ConstLanelet",
939  "An immutable lanelet primitive. Consist of a left and right boundary, attributes and a set of "
940  "traffic rules that apply here. It is not very useful within python, but returned by some lanelet2 algorihms",
941  init<Id, LineString3d, LineString3d, AttributeMap, RegulatoryElementPtrs>(
942  (arg("id"), arg("leftBound"), arg("rightBound"), arg("attributes") = AttributeMap(),
943  arg("regelems") = RegulatoryElementPtrs{})))
944  .def(init<Lanelet>(arg("lanelet"), "Construct from a mutable lanelet"))
945  .def(IsConstPrimitive<ConstLanelet>())
946  .add_property(
947  "centerline", &ConstLanelet::centerline,
948  "Centerline of the lanelet (immutable). This is usualy calculated on-the-fly from the left and right "
949  "bound. The centerline and all its points have ID 0. The centerline can also be overridden by a custom "
950  "centerline, which will usually have nonzero IDs.")
951  .add_property("leftBound", &ConstLanelet::leftBound, "Left boundary of the lanelet")
952  .add_property("rightBound", &ConstLanelet::rightBound, "Right boundary of the lanelet")
953  .add_property("regulatoryElements",
954  make_function(&ConstLanelet::regulatoryElements, return_value_policy<return_by_value>()),
955  "Regulatory elements of the lanelet")
956  .def("trafficLights", constRegelemAs<TrafficLight>,
957  "Returns the list of traffic light regulatory elements of this lanelet")
958  .def("trafficSigns", constRegelemAs<TrafficSign>,
959  "Returns a list of traffic sign regulatory elements of this lanelet")
960  .def("speedLimits", constRegelemAs<SpeedLimit>,
961  "Returns a list of speed limit regulatory elements of this lanelet")
962  .def("rightOfWay", constRegelemAs<RightOfWay>, "Returns right of way regulatory elements of this lanelet")
963  .def("allWayStop", constRegelemAs<AllWayStop>, "Returns all way stop regulatory elements of this lanelet")
964  .def("invert", &ConstLanelet::invert, "Returns inverted lanelet (flipped left/right bound, etc")
965  .def("inverted", &ConstLanelet::inverted, "Returns whether this lanelet has been inverted")
966  .def("polygon2d", &ConstLanelet::polygon2d, "Outline of this lanelet as 2d polygon")
967  .def("polygon3d", &ConstLanelet::polygon3d, "Outline of this lanelet as 3d polygon")
968  .def("resetCache", &ConstLanelet::resetCache,
969  "Reset the cache. Forces update of the centerline if points have changed. This does not clear a custom "
970  "centerline.")
971  .def(
972  "__repr__", +[](const ConstLanelet& llt) {
973  return makeRepr("ConstLanelet", llt.id(), repr(object(llt.leftBound())), repr(object(llt.rightBound())),
974  repr(llt.attributes()), repr(llt.regulatoryElements()));
975  });
976 
977  auto left = static_cast<LineString3d (Lanelet::*)()>(&Lanelet::leftBound);
978  auto right = static_cast<LineString3d (Lanelet::*)()>(&Lanelet::rightBound);
979  auto regelems = static_cast<const RegulatoryElementPtrs& (Lanelet::*)()>(&Lanelet::regulatoryElements);
980 
981  class_<Lanelet, bases<ConstLanelet>>(
982  "Lanelet", "The famous lanelet primitive",
983  init<Id, LineString3d, LineString3d, AttributeMap, RegulatoryElementPtrs>(
984  (arg("id"), arg("leftBound"), arg("rightBound"), arg("attributes") = AttributeMap(),
985  arg("regelems") = RegulatoryElementPtrs{}),
986  "Create Lanelet from an ID, its left and right boundary and (optionally) attributes"))
987  .def(IsPrimitive<Lanelet>())
988  .add_property(
989  "centerline", &Lanelet::centerline, &Lanelet::setCenterline,
990  "Centerline of the lanelet (immutable). This is usualy calculated on-the-fly from the left and right "
991  "bound. The centerline and all its points have ID 0. Assigning a linestring will replace this by a custom, "
992  "persistent centerline.")
993  .add_property("leftBound", left, &Lanelet::setLeftBound, "Left boundary of the lanelet")
994  .add_property("rightBound", right, &Lanelet::setRightBound, "Right boundary of the lanelet")
995  .add_property("regulatoryElements", make_function(regelems, return_value_policy<return_by_value>()),
996  "Regulatory elements of the lanelet")
997  .def("trafficLights", regelemAs<TrafficLight>,
998  "Returns the list of traffic light regulatory elements of this lanelet")
999  .def("trafficSigns", regelemAs<TrafficSign>, "Returns a list of traffic sign regulatory elements of this lanelet")
1000  .def("speedLimits", regelemAs<SpeedLimit>, "Returns a list of speed limit regulatory elements of this lanelet")
1001  .def("rightOfWay", regelemAs<RightOfWay>, "Returns right of way regulatory elements of this lanelet")
1002  .def("allWayStop", regelemAs<AllWayStop>, "Returns all way stop regulatory elements of this lanelet")
1003  .def("addRegulatoryElement", &Lanelet::addRegulatoryElement, arg("regelem"),
1004  "Adds a new regulatory element to the lanelet")
1005  .def("removeRegulatoryElement", &Lanelet::removeRegulatoryElement, arg("regelem"),
1006  "Removes a regulatory element from the lanelet, returns true on success")
1007  .def("invert", &Lanelet::invert, "Returns inverted lanelet (flipped left/right bound, etc)")
1008  .def("inverted", &ConstLanelet::inverted, "Returns whether this lanelet has been inverted")
1009  .def("polygon2d", &ConstLanelet::polygon2d, "Outline of this lanelet as 2D polygon")
1010  .def("polygon3d", &ConstLanelet::polygon3d, "Outline of this lanelet as 3D polygon")
1011  .def(
1012  "__repr__", +[](Lanelet& llt) {
1013  return makeRepr("Lanelet", llt.id(), repr(object(llt.leftBound())), repr(object(llt.rightBound())),
1014  repr(llt.attributes()), repr(ConstLanelet(llt).regulatoryElements()));
1015  });
1016 
1017  class_<LaneletSequence>("LaneletSequence", "A combined lane formed from multiple lanelets", init<ConstLanelets>())
1018  .add_property("centerline", &LaneletSequence::centerline, "Centerline of the combined lanelets")
1019  .add_property("leftBound", &LaneletSequence::leftBound, "Left boundary of the combined lanelets")
1020  .add_property("rightBound", &LaneletSequence::rightBound, "Right boundary of the combined lanelets")
1021  .def("invert", &LaneletSequence::invert, "Returns inverted lanelet sequence (flipped left/right bound, etc)")
1022  .def("polygon2d", &LaneletSequence::polygon2d, "Outline of this lanelet as 2D polygon")
1023  .def("polygon3d", &LaneletSequence::polygon3d, "Outline of this lanelet as 3D polygon")
1024  .def("lanelets", &LaneletSequence::lanelets, "Lanelets that make up this lanelet sequence")
1025  .def("__iter__", iterator<LaneletSequence>())
1026  .def("__len__", &LaneletSequence::size, "Number of lanelets in this sequence")
1027  .def("inverted", &LaneletSequence::inverted, "True if this lanelet sequence is inverted")
1028  .def(
1029  "__repr__", +[](const LaneletSequence& s) { return makeRepr("LaneletSequence", repr(object(s.lanelets()))); })
1030  .def("__getitem__", wrappers::getItem<LaneletSequence>, return_internal_reference<>(),
1031  "Returns a lanelet in the sequence");
1032 
1033  class_<ConstLaneletWithStopLine>("ConstLaneletWithStopLine", "A lanelet with an (optional) stopline", no_init)
1034  .def("__init__",
1035  make_constructor(
1037  return std::make_shared<ConstLaneletWithStopLine>(
1038  ConstLaneletWithStopLine{std::move(lanelet), std::move(stopLine)});
1039  },
1040  default_call_policies(), (arg("lanelet"), arg("stopLine") = Optional<ConstLineString3d>{})),
1041  "Construct from a lanelet and a stop line")
1042  .add_property("lanelet", &ConstLaneletWithStopLine::lanelet, "The lanelet")
1043  .add_property(
1044  "stopLine", +[](const ConstLaneletWithStopLine& self) { return optionalToObject(self.stopLine); },
1045  +[](ConstLaneletWithStopLine& self, const object& value) {
1046  self.stopLine = objectToOptional<LineString3d>(value);
1047  },
1048  "The stop line for the lanelet (can be None)");
1049 
1050  class_<LaneletWithStopLine>("LaneletWithStopLine", "A lanelet with a stopline", no_init)
1051  .def("__init__", make_constructor(
1052  +[](Lanelet lanelet, Optional<LineString3d> stopLine) {
1053  return std::make_shared<LaneletWithStopLine>(
1054  LaneletWithStopLine{std::move(lanelet), std::move(stopLine)});
1055  },
1056  default_call_policies(), (arg("lanelet"), arg("stopLine") = Optional<LineString3d>{})))
1057  .add_property("lanelet", &LaneletWithStopLine::lanelet, "The lanelet")
1058  .add_property(
1059  "stopLine", +[](const LaneletWithStopLine& self) { return optionalToObject(self.stopLine); },
1060  +[](LaneletWithStopLine& self, const object& value) {
1061  self.stopLine = objectToOptional<LineString3d>(value);
1062  },
1063  "The stop line (LineString3d or None)");
1064 
1065  // areas are a bit complicated because the holes are vectors of vectors. For those, we cannot rely on the automatic
1066  // vector-to-list conversion, because area.innerBounds[0].append(ls) would then operate on a temporary list and do
1067  // nothing.
1068  class_<ConstInnerBounds>("ConstInnerBounds", "An immutable list-like type to hold of inner boundaries of an Area",
1069  no_init)
1070  .def("__iter__", iterator<ConstInnerBounds>())
1071  .def("__len__", &InnerBounds::size, "Number of holes")
1072  .def("__getitem__", wrappers::getItem<ConstInnerBounds>, return_value_policy<return_by_value>())
1073  .def(
1074  "__repr__", +[](const ConstInnerBounds& b) { return repr(list(b)); });
1075 
1076  class_<InnerBounds>("InnerBounds", "A list-like type to hold of inner boundaries of an Area", no_init)
1077  .def("__setitem__", wrappers::setItem<InnerBounds, LineStrings3d>)
1078  .def("__delitem__", wrappers::delItem<InnerBounds>)
1079  .def(
1080  "append", +[](InnerBounds& self, LineStrings3d ls) { self.push_back(std::move(ls)); }, "Appends a new hole",
1081  arg("hole"))
1082  .def("__iter__", iterator<InnerBounds>())
1083  .def("__len__", &InnerBounds::size, "Number of holes")
1084  .def("__getitem__", wrappers::getItem<InnerBounds>, return_value_policy<return_by_value>())
1085  .def(
1086  "__repr__", +[](const InnerBounds& b) { return repr(list(b)); });
1087 
1088  class_<ConstArea>(
1089  "ConstArea",
1090  "Represents an immutable area, potentially with holes, in the map. It is composed of a list of linestrings "
1091  "that "
1092  "form the outer boundary and a list of a list of linestrings that represent holes within it.",
1093  boost::python::init<Id, LineStrings3d, InnerBounds, AttributeMap, RegulatoryElementPtrs>(
1094  (arg("id"), arg("outerBound"), arg("innerBounds") = InnerBounds{}, arg("attributes") = AttributeMap{},
1095  arg("regulatoryElements") = RegulatoryElementPtrs{}),
1096  "Construct an area from an ID, its inner and outer boundaries and attributes"))
1097  .def(IsConstPrimitive<ConstArea>())
1098  .add_property("outerBound", &ConstArea::outerBound,
1099  "The outer boundary, a list of clockwise oriented linestrings")
1100  .add_property("innerBounds", &ConstArea::innerBounds,
1101  "The inner boundaries (holes), a list of a list of counter-clockwise oriented linestrings")
1102  .add_property(
1103  "regulatoryElements", +[](ConstArea& self) { return self.regulatoryElements(); },
1104  "The regulatory elements of this area")
1105  .def("outerBoundPolygon", &ConstArea::outerBoundPolygon, "Returns the outer boundary as a CompoundPolygon3d")
1106  .def(
1107  "innerBoundPolygon",
1108  +[](const ConstArea& /*ar*/) {
1109  throw std::runtime_error("innerBoundPolygon is deprecated. Use innerBoundPolygons instead!");
1110  },
1111  "DEPRECATED. Using it throws an exception. Use innerBoundPolygons instead!")
1112  .def("innerBoundPolygons", &ConstArea::innerBoundPolygons,
1113  "Returns the inner boundaries as a list of CompoundPolygon3d")
1114  .def(
1115  "__repr__", +[](const ConstArea& ar) {
1116  return makeRepr("ConstArea", ar.id(), repr(list(ar.outerBound())), repr(object(ar.innerBounds())),
1117  repr(ar.attributes()), repr(ar.regulatoryElements()));
1118  });
1119 
1120  class_<Area, bases<ConstArea>>(
1121  "Area", "Represents an area, potentially with holes, in the map",
1122  boost::python::init<Id, LineStrings3d, InnerBounds, AttributeMap, RegulatoryElementPtrs>(
1123  (arg("id"), arg("outerBound"), arg("innerBounds") = InnerBounds{}, arg("attributes") = AttributeMap{},
1124  arg("regulatoryElements") = RegulatoryElementPtrs{}),
1125  "Construct an area from an ID, its inner and outer boundaries and attributes"))
1126  .def(IsPrimitive<Area>())
1127  .add_property(
1128  "outerBound", +[](Area& self) { return self.outerBound(); }, &Area::setOuterBound,
1129  "The outer boundary, a list of clockwise oriented linestrings")
1130  .add_property(
1131  "innerBounds",
1132  make_function(
1133  // NOLINTNEXTLINE(cppcoreguidelines-pro-type-const-cast)
1134  +[](Area& self) -> InnerBounds& { return const_cast<InnerBounds&>(self.innerBounds()); },
1135  return_internal_reference<>()),
1136  +[](Area& self, const InnerBounds& lss) { self.setInnerBounds(lss); },
1137  "The inner boundaries (holes), a list of a list of counter-clockwise oriented linestrings")
1138  .add_property(
1139  "regulatoryElements", +[](Area& self) { return self.regulatoryElements(); },
1140  "The regulatory elements of this area")
1141  .def("addRegulatoryElement", &Area::addRegulatoryElement, "Appends a new regulatory element", arg("regelem"))
1142  .def("removeRegulatoryElement", &Area::removeRegulatoryElement,
1143  "Removes a regulatory element, retunrs true on success", arg("regelem"))
1144  .def("outerBoundPolygon", &Area::outerBoundPolygon, "Returns the outer boundary as a CompoundPolygon3d")
1145  .def("innerBoundPolygon", +[](const Area& /*ar*/) { throw std::runtime_error("innerBoundPolygon is deprecated. Use innerBoundPolygons instead!");}, "DEPRECATED. Using it throws an exception. Use innerBoundPolygons instead!")
1146  .def("innerBoundPolygons", &Area::innerBoundPolygons,
1147  "Returns the inner boundaries as a list of CompoundPolygon3d")
1148  .def(
1149  "__repr__", +[](Area& ar) {
1150  return makeRepr("Area", ar.id(), repr(list(ar.outerBound())), repr(object(ar.innerBounds())),
1151  repr(ar.attributes()), repr(ConstArea(ar).regulatoryElements()));
1152  });
1153 
1154  using GetParamSig = ConstRuleParameterMap (RegulatoryElement::*)() const;
1155 
1156  class_<RegulatoryElement, boost::noncopyable, RegulatoryElementPtr>(
1157  "RegulatoryElement",
1158  "A Regulatory element defines traffic rules that affect a lanelet. This is a abstract base class that is "
1159  "implemented e.g. by the TrafficLight class.",
1160  no_init)
1161  .def(IsConstPrimitive<RegulatoryElement>())
1162  .add_property("id", &RegulatoryElement::id, &RegulatoryElement::setId)
1163  .add_property("parameters", static_cast<GetParamSig>(&RegulatoryElement::getParameters),
1164  "The parameters (ie traffic signs, lanelets) that affect "
1165  "this RegulatoryElement")
1166  .add_property("roles", &RegulatoryElement::roles, "A list of roles (strings) used in this regulatory element")
1167  .def("find", &RegulatoryElement::find<ConstRuleParameter>, arg("id"),
1168  "Returns a primitive with matching ID, else None")
1169  .def("__len__", &RegulatoryElement::size)
1170  .def(
1171  "__repr__", +[](RegulatoryElement& r) {
1172  return makeRepr("RegulatoryElement", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes()));
1173  });
1174  register_ptr_to_python<RegulatoryElementConstPtr>();
1175 
1176  class_<TrafficLight, boost::noncopyable, std::shared_ptr<TrafficLight>, bases<RegulatoryElement>>(
1177  "TrafficLight", "A traffic light regulatory element", no_init)
1178  .def("__init__", make_constructor(&TrafficLight::make, default_call_policies(),
1179  (arg("id"), arg("attributes"), arg("trafficLights"),
1180  arg("stopLine") = Optional<LineString3d>())))
1181  .add_property(
1182  "stopLine", +[](TrafficLight& self) { return self.stopLine(); }, &TrafficLight::setStopLine,
1183  "The stop line of for this TrafficLight (a LineString or None)")
1184  .add_property("removeStopLine", &TrafficLight::removeStopLine, "Clear the stop line")
1185  .add_property(
1186  "trafficLights", +[](TrafficLight& self) { return self.trafficLights(); },
1187  "Traffic lights. Should all have the same phase.")
1188  .def("addTrafficLight", &TrafficLight::addTrafficLight,
1189  "Add a traffic light. Either a linestring from the left edge to the right edge or an area with the outline "
1190  "of the traffic light.")
1191  .def("removeTrafficLight", &TrafficLight::removeTrafficLight,
1192  "Removes a given traffic light, returns true on success")
1193  .def(
1194  "__repr__", +[](TrafficLight& r) {
1195  return makeRepr("TrafficLight", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes()));
1196  });
1197  implicitly_convertible<std::shared_ptr<TrafficLight>, RegulatoryElementPtr>();
1198 
1199  enum_<ManeuverType>("ManeuverType")
1200  .value("Yield", ManeuverType::Yield)
1201  .value("RightOfWay", ManeuverType::RightOfWay)
1202  .value("Unknown", ManeuverType::Unknown)
1203  .export_values();
1204 
1205  class_<RightOfWay, boost::noncopyable, std::shared_ptr<RightOfWay>, bases<RegulatoryElement>>(
1206  "RightOfWay", "A right of way regulatory element", no_init)
1207  .def("__init__",
1208  make_constructor(&RightOfWay::make, default_call_policies(),
1209  (arg("id"), arg("attributes"), arg("rightOfWayLanelets"), arg("yieldLanelets"),
1210  arg("stopLine") = Optional<LineString3d>{})),
1211  "Creates a right of way regulatory element with an ID from attributes, the list lanelets with right of "
1212  "way, "
1213  "the list of yielding lanelets and an optional stop line")
1214  .add_property(
1215  "stopLine", +[](RightOfWay& self) { return self.stopLine(); }, &RightOfWay::setStopLine,
1216  "The stop line (can be None)")
1217  .def("removeStopLine", &RightOfWay::removeStopLine, "Clear the stop line")
1218  .def("getManeuver", &RightOfWay::getManeuver, "Get maneuver for a lanelet")
1219  .def(
1220  "rightOfWayLanelets", +[](RightOfWay& self) { return self.rightOfWayLanelets(); },
1221  "Returns the lanelets that have the right of way")
1222  .def("addRightOfWayLanelet", &RightOfWay::addRightOfWayLanelet, arg("lanelet"),
1223  "Add another Lanelet that has the right of way. The Lanelet should also reference this regulatory element.")
1224  .def("removeRightOfWayLanelet", &RightOfWay::removeRightOfWayLanelet, arg("lanelet"),
1225  "Removes the right of way for this lanelet, returns true on success.")
1226  .def(
1227  "yieldLanelets", +[](RightOfWay& self) { return self.yieldLanelets(); })
1228  .def("addYieldLanelet", &RightOfWay::addYieldLanelet, arg("lanelet"),
1229  "Adds another lanelet that has to yield. The lanelet should also reference this regolatory element.")
1230  .def("removeYieldLanelet", &RightOfWay::removeYieldLanelet, arg("lanelet"),
1231  "Removes the yielding lanelet, returns true on success.")
1232  .def(
1233  "__repr__", +[](RightOfWay& r) {
1234  return makeRepr("RightOfWay", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes()));
1235  });
1236  implicitly_convertible<std::shared_ptr<RightOfWay>, RegulatoryElementPtr>();
1237 
1238  class_<AllWayStop, boost::noncopyable, std::shared_ptr<AllWayStop>, bases<RegulatoryElement>>(
1239  "AllWayStop", "An all way stop regulatory element", no_init)
1240  .def("__init__",
1241  make_constructor(
1242  &AllWayStop::make, default_call_policies(),
1243  (arg("id"), arg("attributes"), arg("lltsWithStop"), arg("signs") = LineStringsOrPolygons3d{})),
1244  "Constructs an all way stop regulatory element with an ID and attributes from a list of lanelets with "
1245  "their "
1246  "(optional) stop line and an optional list of traffic signs for this rule")
1247  .def(
1248  "lanelets", +[](AllWayStop& self) { return self.lanelets(); }, "Returns the lanelets")
1249  .def(
1250  "stopLines", +[](AllWayStop& self) { return self.stopLines(); },
1251  "Returns the stop lines (same order as the lanelets)")
1252  .def(
1253  "trafficSigns", +[](AllWayStop& self) { return self.trafficSigns(); },
1254  "Returns the list of traffic signs for this rule")
1255  .def("addTrafficSign", &AllWayStop::addTrafficSign, arg("sign"),
1256  "Adds another traffic sign (a Linestring3d from their left to the right edge or a Polygon3d with the "
1257  "outline)")
1258  .def("removeTrafficSign", &AllWayStop::removeTrafficSign, arg("sign"),
1259  "Removes a traffic sign, returns True on success")
1260  .def("addLanelet", &AllWayStop::addLanelet, arg("lanelet"),
1261  "Adds another lanelet to the all way stop. The lanelet should also reference this all way stop.")
1262  .def("removeLanelet", &AllWayStop::removeLanelet, arg("lanelet"),
1263  "Removes a lanelet from the all way stop, returns True on success.")
1264  .def(
1265  "__repr__", +[](AllWayStop& r) {
1266  return makeRepr("AllWayStop", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes()));
1267  });
1268  implicitly_convertible<std::shared_ptr<AllWayStop>, RegulatoryElementPtr>();
1269 
1270  class_<TrafficSignsWithType, std::shared_ptr<TrafficSignsWithType>>(
1271  "TrafficSignsWithType", "Combines a traffic sign with its type, used for the TrafficSign regulatory element",
1272  no_init)
1273  .def("__init__", make_constructor(+[](LineStringsOrPolygons3d ls) {
1274  return std::make_shared<TrafficSignsWithType>(TrafficSignsWithType{std::move(ls)});
1275  }),
1276  "Construct from a Linestring/Polygon with a type deduced from the attributes.")
1277  .def("__init__", make_constructor(+[](LineStringsOrPolygons3d ls, std::string type) {
1278  return std::make_shared<TrafficSignsWithType>(TrafficSignsWithType{std::move(ls), std::move(type)});
1279  }),
1280  "Construct from a Linestring/Polygon with an explicit type")
1281  .def_readwrite("trafficSigns", &TrafficSignsWithType::trafficSigns)
1282  .def_readwrite("type", &TrafficSignsWithType::type);
1283 
1284  class_<TrafficSign, boost::noncopyable, std::shared_ptr<TrafficSign>, bases<RegulatoryElement>>(
1285  "TrafficSign", "A generic traffic sign regulatory element", no_init)
1286  .def("__init__",
1287  make_constructor(&TrafficSign::make, default_call_policies(),
1288  (arg("id"), arg("attributes"), arg("trafficSigns"),
1289  arg("cancellingTrafficSigns") = TrafficSignsWithType{}, arg("refLines") = LineStrings3d(),
1290  arg("cancelLines") = LineStrings3d())),
1291  "Constructs a traffic sign withan ID and attributes from a traffic signs with type object and optionally "
1292  "cancelling traffic signs, lines from where the rule starts and lines where it ends")
1293  .def(
1294  "trafficSigns", +[](TrafficSign& self) { return self.trafficSigns(); },
1295  "Get a list of all traffic signs (linestrings or polygons)")
1296  .def(
1297  "cancellingTrafficSigns", +[](TrafficSign& self) { return self.cancellingTrafficSigns(); },
1298  "Get a list of all cancelling traffic signs (linestrings or polygons). These are the signs that mark the "
1299  "end "
1300  "of a rule. E.g. a sign that cancels a speed limit.")
1301  .def(
1302  "refLines", +[](TrafficSign& self) { return self.refLines(); },
1303  "List of linestrings after which the traffic rule becomes valid")
1304  .def(
1305  "cancelLines", +[](TrafficSign& self) { return self.cancelLines(); },
1306  "List of linestrings after which the rule becomes invalid")
1307  .def("addTrafficSign", &TrafficSign::addTrafficSign, arg("trafficSign"),
1308  "Add another traffic sign (linestring or polygon)")
1309  .def("removeTrafficSign", &TrafficSign::removeTrafficSign, arg("trafficSign"),
1310  "Remove a traffic sign, returns True on success")
1311  .def("addRefLine", &TrafficSign::addRefLine, arg("refLine"), "Add a ref line")
1312  .def("removeRefLine", &TrafficSign::removeRefLine, arg("refLine"), "Remove a ref line, returns True on success")
1313  .def("addCancellingTrafficSign", &TrafficSign::addCancellingTrafficSign, arg("cancellingTrafficSign"),
1314  "Add a cancelling traffic sign")
1315  .def("removeCancellingTrafficSign", &TrafficSign::removeCancellingTrafficSign, arg("cancellingTrafficSign"),
1316  "Remove cancelling traffic sign, return True on success")
1317  .def("addCancellingRefLine", &TrafficSign::addCancellingRefLine, arg("cancelLine"), "Add a cancelling ref line")
1318  .def("removeCancellingRefLine", &TrafficSign::removeCancellingRefLine, arg("cancelLine"),
1319  "Remove a cancelling ref line, returns True on success")
1320  .def("type", &TrafficSign::type,
1321  "Returns the type (string) of the traffic sign that start this rule. This is deduced from the traffic sign "
1322  "itself or "
1323  "the explicitly set type. All signs are assumed to have the same type.")
1324  .def("cancelTypes", &TrafficSign::cancelTypes,
1325  "Returns types of the cancelling traffic signs (a list of strings) if it exists.")
1326  .def(
1327  "__repr__", +[](TrafficSign& r) {
1328  return makeRepr("TrafficSign", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes()));
1329  });
1330 
1331  implicitly_convertible<std::shared_ptr<TrafficSign>, RegulatoryElementPtr>();
1332 
1333  implicitly_convertible<std::shared_ptr<SpeedLimit>, RegulatoryElementPtr>();
1334 
1335  class_<SpeedLimit, boost::noncopyable, std::shared_ptr<SpeedLimit>, bases<TrafficSign>>( // NOLINT
1336  "SpeedLimit", "A speed limit regulatory element. This is a special case of a traffic sign regulatory element.",
1337  no_init)
1338  .def("__init__", make_constructor(&TrafficSign::make, default_call_policies(),
1339  (arg("id"), arg("attributes"), arg("trafficSigns"),
1340  arg("cancellingTrafficSigns") = TrafficSignsWithType{},
1341  arg("refLines") = LineStrings3d(), arg("cancelLines") = LineStrings3d())))
1342  .def(
1343  "__repr__", +[](SpeedLimit& r) {
1344  return makeRepr("SpeedLimit", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes()));
1345  });
1346 
1347  class_<PrimitiveLayer<Area>, boost::noncopyable>("PrimitiveLayerArea", no_init); // NOLINT
1348  class_<PrimitiveLayer<Lanelet>, boost::noncopyable>("PrimitiveLayerLanelet", no_init); // NOLINT
1349 
1350  wrapLayer<AreaLayer, bases<PrimitiveLayer<Area>>>("AreaLayer")
1351  .def(
1352  "findUsages", +[](AreaLayer& self, RegulatoryElementPtr& e) { return self.findUsages(e); }, arg("regelem"),
1353  "Find areas with this regulatory element")
1354  .def(
1355  "findUsages", +[](AreaLayer& self, ConstLineString3d& ls) { return self.findUsages(ls); }, arg("ls"),
1356  "Find areas with this linestring");
1357  wrapLayer<LaneletLayer, bases<PrimitiveLayer<Lanelet>>>("LaneletLayer")
1358  .def(
1359  "findUsages", +[](LaneletLayer& self, RegulatoryElementPtr& e) { return self.findUsages(e); }, arg("regelem"),
1360  "Find lanelets with this regualtory element")
1361  .def(
1362  "findUsages", +[](LaneletLayer& self, ConstLineString3d& ls) { return self.findUsages(ls); }, arg("ls"),
1363  "Lanelets with this linestring");
1364  wrapLayer<PolygonLayer>("PolygonLayer")
1365  .def(
1366  "findUsages", +[](PolygonLayer& self, ConstPoint3d& p) { return self.findUsages(p); }, arg("point"),
1367  "Find polygons with this point");
1368  wrapLayer<LineStringLayer>("LineStringLayer")
1369  .def(
1370  "findUsages", +[](LineStringLayer& self, ConstPoint3d& p) { return self.findUsages(p); }, arg("point"),
1371  "Find linestrings with this point");
1372  wrapLayer<PointLayer>("PointLayer");
1373  wrapLayer<RegulatoryElementLayer>("RegulatoryElementLayer");
1374 
1375  class_<LaneletMapLayers, boost::noncopyable>("LaneletMapLayers", "Container for the layers of a lanelet map")
1376  .def_readonly("laneletLayer", &LaneletMap::laneletLayer,
1377  "Lanelets of this map (works like a dictionary with ID as key and Lanelet as value)")
1378  .def_readonly("areaLayer", &LaneletMap::areaLayer,
1379  "Areas of this map (works like a dictionary with ID as key and Area as value)")
1380  .def_readonly(
1381  "regulatoryElementLayer", &LaneletMap::regulatoryElementLayer,
1382  "Regulatory elements of this map (works like a dictionary with ID as key and RegulatoryElement as value)")
1383  .def_readonly("lineStringLayer", &LaneletMap::lineStringLayer,
1384  "Linestrings of this map (works like a dictionary with ID as key and Linestring3d as value)")
1385  .def_readonly("polygonLayer", &LaneletMap::polygonLayer,
1386  "Polygons of this map (works like a dictionary with ID as key and Polygon3d as value)")
1387  .def_readonly("pointLayer", &LaneletMap::pointLayer,
1388  "Points of this map (works like a dictionary with ID as key and Point3d as value)");
1389 
1390  class_<LaneletMap, bases<LaneletMapLayers>, LaneletMapPtr, boost::noncopyable>(
1391  "LaneletMap",
1392  "A lanelet map collects lanelet primitives. It can be used for writing and loading and creating routing "
1393  "graphs. "
1394  "It also offers geometrical and relational queries for its objects. Note that this is not the right object for "
1395  "querying neigborhood relations. Create a lanelet2.routing.RoutingGraph for this.\nNote that there is a "
1396  "utility "
1397  "function 'createMapFromX' to create a map from a list of primitives.",
1398  init<>("Create an empty lanelet map"))
1399  .def("add", selectAdd<Point3d>(), arg("point"),
1400  "Add a point to the map. It its ID is zero, it will be set to a unique value.")
1401  .def("add", selectAdd<Lanelet>(), arg("lanelet"),
1402  "Add a lanelet and all its subobjects to the map. It its (or its subobjects IDs) are zero, it will be set "
1403  "to a unique value.")
1404  .def("add", selectAdd<Area>(), arg("area"),
1405  "Add an area and all its subobjects to the map. It its (or its subobjects IDs) are zero, it will be set to "
1406  "a unique value.")
1407  .def("add", selectAdd<LineString3d>(), arg("linestring"),
1408  "Add a linestring and all its points to the map. It its (or its points IDs) are zero, it will be set to a "
1409  "unique value.")
1410  .def("add", selectAdd<Polygon3d>(), arg("polygon"),
1411  "Add a polygon and all its points to the map. It its (or its points IDs) are zero, it will be set to a "
1412  "unique value.")
1413  .def("add", selectAdd<const RegulatoryElementPtr&>(), arg("regelem"),
1414  "Add a regulatory element and all its subobjects to the map. It its (or its subobjects IDs) are zero, it "
1415  "will be set to a unique value.");
1416  register_ptr_to_python<LaneletMapConstPtr>();
1417 
1418  class_<LaneletSubmap, bases<LaneletMapLayers>, LaneletSubmapPtr, boost::noncopyable>(
1419  "LaneletSubmap",
1420  "A submap manages parts of a lanelet map. An important difference is that adding an object to the map will "
1421  "*not* "
1422  "add its subobjects too, making it more efficient to create. Apart from that, it offers a similar "
1423  "functionality "
1424  "compared to a lanelet map.",
1425  init<>("Create an empty lanelet submap"))
1426  .def(
1427  "laneletMap", +[](LaneletSubmap& self) { return LaneletMapPtr{self.laneletMap()}; },
1428  "Create a lanelet map of this submap that also holds all subobjects. This is a potentially costly "
1429  "operation.")
1430  .def("add", selectSubmapAdd<Point3d>(), arg("point"), "Add a point to the submap")
1431  .def("add", selectSubmapAdd<Lanelet>(), arg("lanelet"),
1432  "Add a lanelet to the submap, without its subobjects. If its ID is zero it will be set to a unique value "
1433  "instead.")
1434  .def("add", selectSubmapAdd<Area>(), arg("area"),
1435  "Add an area to the submap, without its subobjects. If its ID is zero it will be set to a unique value "
1436  "instead.")
1437  .def("add", selectSubmapAdd<LineString3d>(), arg("linestring"),
1438  "Add a linesting to the submap, without its points. If its ID is zero it will be set to a unique value "
1439  "instead.")
1440  .def("add", selectSubmapAdd<Polygon3d>(), arg("polygon"),
1441  "Add a polygon to the submap, without its points. If its ID is zero it will be set to a unique value "
1442  "instead.")
1443  .def("add", selectSubmapAdd<const RegulatoryElementPtr&>(), arg("regelem"),
1444  "Add a regulatory element to the submap, without its subobjects. If its ID is zero it will be set to a "
1445  "unique value "
1446  "instead.");
1447  register_ptr_to_python<LaneletSubmapConstPtr>();
1448 
1449  def("getId", static_cast<Id (&)()>(utils::getId), "Returns a globally unique id");
1450  def("registerId", &utils::registerId, "Registers an id (so that it will not be returned by getId)");
1451 
1452  def("createMapFromPoints", createMapWrapper<Points3d>, arg("points"), "Create map from a list of points");
1453  def("createMapFromLineStrings", createMapWrapper<LineStrings3d>, arg("linestrings"),
1454  "Create map from a list of linestrings");
1455  def("createMapFromPolygons", createMapWrapper<Polygons3d>, arg("polygons"), "Create map from a list of polygons");
1456  def("createMapFromLanelets", createMapWrapper<Lanelets>, arg("lanelets"), "Create map from a list of lanelets");
1457  def("createMapFromAreas", createMapWrapper<Areas>, arg("areas"), "Create map from a list of areas");
1458 
1459  def("createSubmapFromPoints", createSubmapWrapper<Points3d>, arg("points"), "Create sbumap from a list of points");
1460  def("createSubmapFromLineStrings", createSubmapWrapper<LineStrings3d>, arg("linestrings"),
1461  "Create submap from a list of linestrings");
1462  def("createSubmapFromPolygons", createSubmapWrapper<Polygons3d>, arg("polygons"),
1463  "Create submap from a list of polygons");
1464  def("createSubmapFromLanelets", createSubmapWrapper<Lanelets>, arg("lanelets"),
1465  "Create submap from a list of lanelets");
1466  def("createSubmapFromAreas", createSubmapWrapper<Areas>, arg("areas"), "Create submap from a list of areas");
1467 }
Optional< ConstLanelet > lanelet() const
Id id() const noexcept
ConstInnerBounds innerBounds() const
BasicPoint p
Optional< T > objectToOptional(const object &o)
Definition: routing.cpp:51
const InnerBounds & innerBounds()
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: core.cpp:466
object optionalToObject(const Optional< T > &v)
Definition: routing.cpp:46
double & y() noexcept
std::vector< ConstLineString3d > ConstLineStrings3d
double & z() noexcept
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
std::vector< RegulatoryElementPtr > RegulatoryElementPtrs
std::shared_ptr< LaneletMap > LaneletMapPtr
type
RegulatoryElementConstPtrs regulatoryElements() const
int64_t Id
std::pair< iterator, bool > insert(const value_type &v)
Eigen::Vector3d BasicPoint3d
const std::string & value() const
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
Optional< ConstArea > area() const
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
const AttributeMap & attributes() const
std::shared_ptr< LaneletSubmap > LaneletSubmapPtr
double z() const noexcept
py::to_python_converter< T, VariantToObject< T > > VariantConverter
Definition: converter.h:228
RegulatoryElementConstPtrs regulatoryElements() const
std::vector< LineStrings3d > InnerBounds
BasicPolygon3d right
ConstLineStrings3d outerBound() const
double & y() noexcept
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
BasicPolygon3d left
const VectorType &() min() const
const LineStrings3d & outerBound()
std::vector< Point3d > Points3d
py::to_python_converter< T, VectorToList< T > > VectorToListConverter
Definition: converter.h:219
Eigen::AlignedBox3d BoundingBox3d
const std::shared_ptr< const RegulatoryElementData > & constData() const
boost::optional< T > Optional
const VectorType &() max() const
ConstLanelets lanelets() const
std::vector< LineStringOrPolygon3d > LineStringsOrPolygons3d
double & x() noexcept
ConstLineString3d leftBound() const
double & x() noexcept
LineString3d leftBound()
LineString3d rightBound()
ConstLineString3d rightBound() const
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
py::to_python_converter< T, WeakToObject< T > > WeakConverter
Definition: converter.h:225
AttributeMap & attributes() noexcept
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
PyPair< typename T::first_type, typename T::second_type > PairConverter
Definition: converter.h:231
std::vector< Area > Areas
py::to_python_converter< lanelet::Optional< T >, OptionalToObject< T > > OptionalConverter
Definition: converter.h:222
std::vector< ConstLineStrings3d > ConstInnerBounds
std::vector< Polygon2d > Polygons2d
std::vector< LineString3d > LineStrings3d
Optional< LineString3d > lineString() const
double d
std::vector< ConstLanelet > ConstLanelets


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:59