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


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