6 #include <lanelet2_core/primitives/RegulatoryElement.h>
8 #include <boost/python/object_core.hpp>
9 #include <boost/python/return_by_value.hpp>
10 #include <boost/python/return_internal_reference.hpp>
14 #include "lanelet2_core/primitives/Area.h"
15 #include "lanelet2_core/primitives/Polygon.h"
20 using namespace boost::python;
48 return repr(
object(a));
52 if (regelems.empty()) {
55 return repr(list(regelems));
58 template <
typename LaneletT>
59 std::string
makeLaneletRepr(
const std::string& displayName,
bool withRegelems, LaneletT& llt) {
61 return makeRepr(
"Lanelet", llt.id(),
repr(
object(llt.leftBound())),
repr(
object(llt.rightBound())),
64 return makeRepr(
"Lanelet", llt.id(),
repr(
object(llt.leftBound())),
repr(
object(llt.rightBound())),
65 repr(llt.attributes()));
68 template <
typename AreaT>
69 std::string
makeAreaRepr(
const std::string& displayName,
bool withRegelems, AreaT& area) {
71 return makeRepr(
"Area", area.id(),
repr(
object(area.outerBound())),
repr(
object(area.innerBounds())),
74 return makeRepr(
"Area", area.id(),
repr(
object(area.outerBound())),
repr(
object(area.innerBounds())),
75 repr(area.attributes()));
79 using namespace boost::python;
80 auto paramsDict = dict(ruleParams);
83 auto values = paramsDict.values();
84 for (
int v = 0; v < len(values); ++v) {
85 list l = extract<list>(values[v]);
86 for (
int i = 0; i < len(l); ++i) {
87 if (extract<Lanelet>(l[i]).check()) {
90 if (extract<Area>(l[i]).check()) {
95 return repr(paramsDict);
103 struct AttributeToPythonStr {
104 static PyObject* convert(
Attribute const& s) {
return boost::python::incref(boost::python::object(s.
value()).ptr()); }
107 struct AttributeFromPythonStr {
108 AttributeFromPythonStr() {
109 boost::python::converter::registry::push_back(&convertible, &construct, boost::python::type_id<Attribute>());
112 static void* convertible(PyObject* objPtr) {
113 #if PY_MAJOR_VERSION < 3
114 return PyString_Check(objPtr) ? objPtr :
nullptr;
116 return PyUnicode_Check(objPtr) ? objPtr :
nullptr;
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);
124 auto* pyStr = PyUnicode_AsUTF8String(objPtr);
125 const char* value = PyBytes_AsString(pyStr);
127 if (value ==
nullptr) {
128 boost::python::throw_error_already_set();
130 using StorageType = boost::python::converter::rvalue_from_python_storage<Attribute>;
131 void* storage =
reinterpret_cast<StorageType*
>(data)->storage.bytes;
133 data->convertible = storage;
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)) {
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();
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));
155 using StorageType = converter::rvalue_from_python_storage<AttributeMap>;
156 void* storage =
reinterpret_cast<StorageType*
>(data)->storage.bytes;
158 data->convertible = storage;
162 struct LineStringOrPolygonToObject {
165 return incref(
object(*v.
polygon()).ptr());
170 return incref(
object().ptr());
174 struct ConstLineStringOrPolygonToObject {
177 return incref(
object(*v.
polygon()).ptr());
182 return incref(
object().ptr());
186 struct ConstLaneletOrAreaToObject {
189 return incref(
object(*v.
area()).ptr());
192 return incref(
object(*v.
lanelet()).ptr());
194 return incref(
object().ptr());
198 struct ConstWeakLaneletToObject {
200 return incref(
object(v.
lock()).ptr());
206 using K =
typename T::key_type;
207 using V =
typename T::mapped_type;
208 using Iter =
typename T::const_iterator;
210 MapItem& fromPython() {
211 &MapItem::convertible, &MapItem::init, boost::python::type_id<T>();
214 static list keys(T
const& x) {
216 for (
auto it = x.begin(); it != x.end(); ++it) {
221 static list values(T
const& x) {
223 for (
auto it = x.begin(); it != x.end(); ++it) {
224 t.append(it->second);
228 static list items(T
const& x) {
230 for (
auto it = x.begin(); it != x.end(); ++it) {
231 t.append(boost::python::make_tuple(it->first, it->second));
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>();
239 boost::python::list keys = pyDict.keys();
240 for (
int i = 0; i < len(keys); ++i) {
241 boost::python::extract<K> extractedKey(keys[i]);
242 if (!extractedKey.check()) {
243 PyErr_SetString(PyExc_KeyError,
"Key invalid!");
244 throw_error_already_set();
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();
252 V value = extractedVal;
259 template <
typename T>
260 void setXWrapper(T& obj,
double x) {
263 template <
typename T>
264 void setYWrapper(T& obj,
double y) {
268 template <
typename T>
269 void setZWrapper(T& obj,
double z) {
272 template <
typename T>
273 double getXWrapper(
const T& obj) {
276 template <
typename T>
277 double getYWrapper(
const T& obj) {
281 template <
typename T>
282 double getZWrapper(
const T& obj) {
286 template <
typename Func>
287 auto getRefFunc(Func&& f) {
288 return make_function(std::forward<Func>(f), return_internal_reference<>());
291 template <
typename T>
292 void setAttributeWrapper(T& obj,
const AttributeMap& attr) {
293 obj.attributes() = attr;
296 template <
typename PrimT>
297 class IsPrimitive :
public def_visitor<IsPrimitive<PrimT>> {
298 using ConstT =
const PrimT;
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.");
310 c.def(self_ns::str(self_ns::self));
312 "__hash__", +[](
const PrimT&
self) {
return std::hash<PrimT>()(
self); });
316 template <
typename PrimT>
317 class IsConstPrimitive :
public def_visitor<IsConstPrimitive<PrimT>> {
318 friend class def_visitor_access;
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.");
329 c.def(self_ns::str(self_ns::self));
331 "__hash__", +[](
const PrimT&
self) {
return std::hash<PrimT>()(
self); });
335 template <
typename LsT,
bool InternalRef = true>
336 class IsConstLineString :
public def_visitor<IsConstLineString<LsT, InternalRef>> {
337 friend class def_visitor_access;
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);
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<>());
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>());
358 bool internalRef_{
false};
361 template <
typename LsT>
362 class IsLineString :
public def_visitor<IsLineString<LsT>> {
363 friend class def_visitor_access;
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");
376 template <
typename ClassT>
377 void addGetitem(ClassT& c)
const {
378 c.def(
"__getitem__", wrappers::getItem<LsT>, return_internal_reference<>());
382 template <
typename T>
383 class IsHybridMap :
public def_visitor<IsHybridMap<T>> {
384 friend class def_visitor_access;
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")
399 template <
typename T>
400 T addWrapper(
const T& rhs,
const T& lhs) {
404 template <
typename T>
405 T subWrapper(
const T& rhs,
const T& lhs) {
409 template <
typename T1,
typename T2>
410 T1 mulWrapper(
const T1& rhs,
const T2& lhs) {
411 return (rhs * lhs).eval();
414 template <
typename T1,
typename T2>
415 T2 rmulWrapper(
const T1& rhs,
const T2& lhs) {
416 return (rhs * lhs).eval();
419 template <
typename T1,
typename T2>
420 T1 divWrapper(
const T1& rhs,
const T2& lhs) {
421 return (rhs / lhs).eval();
424 template <
typename T>
425 using SetAttrSig = void (T::*)(
const std::string&,
const Attribute&);
427 template <
typename T>
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);
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")
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")
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");
455 template <
typename PrimT>
457 return static_cast<void (
LaneletMap::*)(PrimT)
>(&LaneletMap::add);
459 template <
typename PrimT>
460 auto selectSubmapAdd() {
461 return static_cast<void (
LaneletSubmap::*)(PrimT)
>(&LaneletSubmap::add);
464 template <
typename RegelemT>
465 std::vector<std::shared_ptr<RegelemT>> regelemAs(
Lanelet& llt) {
469 template <
typename RegelemT>
470 std::vector<std::shared_ptr<RegelemT>> constRegelemAs(
ConstLanelet& llt) {
472 [](
auto& e) { return std::const_pointer_cast<RegelemT>(e); });
475 template <
typename PrimT>
477 return utils::createMap(prim);
480 template <
typename PrimT>
482 return utils::createSubmap(prim);
485 template <
typename T>
487 return v ? object(*v) : object();
490 template <
typename T>
500 class_<ReprWrapper>(
"_ReprWrapper",
"Internal helper class for repr", no_init)
501 .def(
"__repr__", &ReprWrapper::operator(),
"Returns the string representation of this object");
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>)
514 .def(self_ns::str(self_ns::self));
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>)
525 "__repr__", +[](Eigen::Vector2d
p) {
return makeRepr(
"Vector2d",
p.x(),
p.y()); })
526 .def(self_ns::str(self_ns::self));
528 implicitly_convertible<Eigen::Vector2d, BasicPoint2d>();
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>)
542 .def(self_ns::str(self_ns::self));
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"))
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"))
579 return makeRepr(
"BoundingBox3d",
repr(
object(box.min())),
repr(
object(box.max())));
582 boost::python::to_python_converter<Attribute, AttributeToPythonStr>();
584 using ::converters::IterableConverter;
587 using ::converters::ToOptionalConverter;
592 VariantConverter<RuleParameter>();
593 VariantConverter<ConstRuleParameter>();
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();
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>();
666 PairConverter<std::pair<BasicPoint2d, BasicPoint2d>>();
667 PairConverter<std::pair<BasicPoint3d, BasicPoint3d>>();
669 WeakConverter<WeakLanelet>();
670 WeakConverter<WeakArea>();
675 .fromPython<Points2d>()
677 .fromPython<ConstLineStrings2d>()
679 .fromPython<LineStrings2d>()
681 .fromPython<Polygons3d>()
683 .fromPython<Lanelets>()
685 .fromPython<LaneletsWithStopLines>()
687 .fromPython<ConstAreas>()
689 .fromPython<LineStringsOrPolygons3d>()
694 to_python_converter<LineStringOrPolygon3d, LineStringOrPolygonToObject>();
695 to_python_converter<ConstLineStringOrPolygon3d, ConstLineStringOrPolygonToObject>();
696 to_python_converter<ConstLaneletOrArea, ConstLaneletOrAreaToObject>();
697 to_python_converter<ConstWeakLanelet, ConstWeakLaneletToObject>();
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>();
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))
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>())
719 class_<ConstRuleParameterMap>(
"ConstRuleParameterMap", init<>(
"ConstRuleParameterMap()"))
720 .def(IsHybridMap<ConstRuleParameterMap>())
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",
727 .def(IsConstPrimitive<ConstPoint2d>())
728 .add_property(
"x", getXWrapper<ConstPoint2d>,
"x coordinate")
729 .add_property(
"y", getYWrapper<ConstPoint2d>,
"y coordinate")
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>>(
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")
748 .def(IsPrimitive<Point2d>());
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",
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")
761 return makeRepr(
"ConstPoint3d",
p.id(),
p.x(),
p.y(),
p.z(),
repr(
p.attributes()));
763 .def(
"basicPoint", &ConstPoint3d::basicPoint, return_internal_reference<>(),
764 "Returns a plain 3D point primitive (no ID, no attributes) for efficient geometry operations");
766 class_<Point3d, bases<ConstPoint3d>>(
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")
781 .def(IsPrimitive<Point3d>());
783 class_<GPSPoint, std::shared_ptr<GPSPoint>>(
"GPSPoint",
"A raw GPS point", no_init)
784 .def(
"__init__", make_constructor(
786 +[](
double lat,
double lon,
double alt) {
787 return std::make_shared<GPSPoint>(
GPSPoint({lat, lon, alt}));
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]")
796 class_<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>())
811 class_<LineString2d, bases<ConstLineString2d>>(
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 "
825 "returned in reversed order")
831 .def(IsLineString<LineString2d>());
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 "
842 "returned in reversed order")
848 .def(IsConstLineString<ConstLineString3d>())
849 .def(IsConstPrimitive<ConstLineString3d>());
851 class_<LineString3d, bases<ConstLineString3d>>(
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")
867 .def(IsLineString<LineString3d>())
868 .def(IsPrimitive<LineString3d>());
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")
883 .def(IsConstLineString<ConstHybridLineString2d, false>())
884 .def(IsConstPrimitive<ConstHybridLineString2d>());
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")
899 .def(IsConstLineString<ConstHybridLineString3d, false>())
900 .def(IsConstPrimitive<ConstHybridLineString3d>());
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");
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");
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>())
926 .def(IsConstPrimitive<ConstPolygon2d>());
928 class_<ConstPolygon3d>(
929 "ConstPolygon3d",
"A three-dimensional lanelet polygon",
930 init<Id, Points3d, AttributeMap>((arg(
"id"), arg(
"points"), arg(
"attributes") =
AttributeMap())))
936 .def(IsConstLineString<ConstPolygon3d>())
937 .def(IsConstPrimitive<ConstPolygon3d>());
939 class_<Polygon2d, bases<ConstPolygon2d>>(
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"))
947 .def(IsLineString<Polygon2d>())
948 .def(IsPrimitive<Polygon2d>());
950 class_<Polygon3d, bases<ConstPolygon3d>>(
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())))
957 .def(IsLineString<Polygon3d>())
958 .def(IsPrimitive<Polygon3d>());
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");
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");
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"))
983 .def(IsConstLineString<ConstHybridPolygon2d, false>())
984 .def(IsConstPrimitive<ConstHybridPolygon2d>());
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"))
995 .def(IsConstLineString<ConstHybridPolygon3d, false>())
996 .def(IsConstPrimitive<ConstHybridPolygon3d>());
998 class_<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(),
1005 .def(init<Lanelet>(arg(
"lanelet"),
"Construct from a mutable lanelet"))
1006 .def(IsConstPrimitive<ConstLanelet>())
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 "
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(),
1047 "Create Lanelet from an ID, its left and right boundary and (optionally) attributes"))
1048 .def(IsPrimitive<Lanelet>())
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")
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")
1087 .def(
"__getitem__", wrappers::getItem<LaneletSequence>, return_internal_reference<>(),
1088 "Returns a lanelet in the sequence");
1090 class_<ConstLaneletWithStopLine>(
"ConstLaneletWithStopLine",
"A lanelet with an (optional) stopline", no_init)
1094 return std::make_shared<ConstLaneletWithStopLine>(
1098 "Construct from a lanelet and a stop line")
1099 .add_property(
"lanelet", &ConstLaneletWithStopLine::lanelet,
"The lanelet")
1103 self.stopLine = objectToOptional<LineString3d>(value);
1105 "The stop line for the lanelet (can be None)");
1107 class_<LaneletWithStopLine>(
"LaneletWithStopLine",
"A lanelet with a stopline", no_init)
1108 .def(
"__init__", make_constructor(
1110 return std::make_shared<LaneletWithStopLine>(
1114 .add_property(
"lanelet", &LaneletWithStopLine::lanelet,
"The lanelet")
1118 self.stopLine = objectToOptional<LineString3d>(value);
1120 "The stop line (LineString3d or None)");
1125 class_<ConstInnerBounds>(
"ConstInnerBounds",
"An immutable list-like type to hold of inner boundaries of an Area",
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>())
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>)
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)); });
1145 "Represents an immutable area, potentially with holes, in the map. It is composed of a list of linestrings "
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>(
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")
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")
1162 "innerBoundPolygon",
1164 throw std::runtime_error(
"innerBoundPolygon is deprecated. Use innerBoundPolygons instead!");
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")
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>(
1176 "Construct an area from an ID, its inner and outer boundaries and attributes"))
1177 .def(IsPrimitive<Area>())
1179 "outerBound", +[](
Area&
self) {
return self.outerBound(); }, &Area::setOuterBound,
1180 "The outer boundary, a list of clockwise oriented linestrings")
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")
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& ) {
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")
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.",
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)
1224 register_ptr_to_python<RegulatoryElementConstPtr>();
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"),
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")
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")
1249 enum_<ManeuverType>(
"ManeuverType")
1250 .value(
"Yield", ManeuverType::Yield)
1251 .value(
"RightOfWay", ManeuverType::RightOfWay)
1252 .value(
"Unknown", ManeuverType::Unknown)
1255 class_<RightOfWay, boost::noncopyable, std::shared_ptr<RightOfWay>, bases<RegulatoryElement>>(
1256 "RightOfWay",
"A right of way regulatory element", no_init)
1258 make_constructor(&RightOfWay::make, default_call_policies(),
1259 (arg(
"id"), arg(
"attributes"), arg(
"rightOfWayLanelets"), arg(
"yieldLanelets"),
1261 "Creates a right of way regulatory element with an ID from attributes, the list lanelets with right of "
1263 "the list of yielding lanelets and an optional stop line")
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")
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.")
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.")
1288 class_<AllWayStop, boost::noncopyable, std::shared_ptr<AllWayStop>, bases<RegulatoryElement>>(
1289 "AllWayStop",
"An all way stop regulatory element", no_init)
1292 &AllWayStop::make, default_call_policies(),
1294 "Constructs an all way stop regulatory element with an ID and attributes from a list of lanelets with "
1296 "(optional) stop line and an optional list of traffic signs for this rule")
1298 "lanelets", +[](
AllWayStop&
self) {
return self.lanelets(); },
"Returns the lanelets")
1300 "stopLines", +[](
AllWayStop&
self) {
return self.stopLines(); },
1301 "Returns the stop lines (same order as the lanelets)")
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 "
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.")
1320 class_<TrafficSignsWithType, std::shared_ptr<TrafficSignsWithType>>(
1321 "TrafficSignsWithType",
"Combines a traffic sign with its type, used for the TrafficSign regulatory element",
1326 "Construct from a Linestring/Polygon with a type deduced from the attributes.")
1330 "Construct from a Linestring/Polygon with an explicit type")
1331 .def_readwrite(
"trafficSigns", &TrafficSignsWithType::trafficSigns)
1334 class_<TrafficSign, boost::noncopyable, std::shared_ptr<TrafficSign>, bases<RegulatoryElement>>(
1335 "TrafficSign",
"A generic traffic sign regulatory element", no_init)
1337 make_constructor(&TrafficSign::make, default_call_policies(),
1338 (arg(
"id"), arg(
"attributes"), arg(
"trafficSigns"),
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")
1344 "trafficSigns", +[](
TrafficSign&
self) {
return self.trafficSigns(); },
1345 "Get a list of all traffic signs (linestrings or polygons)")
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 "
1350 "of a rule. E.g. a sign that cancels a speed limit.")
1352 "refLines", +[](
TrafficSign&
self) {
return self.refLines(); },
1353 "List of linestrings after which the traffic rule becomes valid")
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")
1371 "Returns the type (string) of the traffic sign that start this rule. This is deduced from the traffic sign "
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.")
1385 class_<SpeedLimit, boost::noncopyable, std::shared_ptr<SpeedLimit>, bases<TrafficSign>>(
1386 "SpeedLimit",
"A speed limit regulatory element. This is a special case of a traffic sign regulatory element.",
1388 .def(
"__init__", make_constructor(&TrafficSign::make, default_call_policies(),
1389 (arg(
"id"), arg(
"attributes"), arg(
"trafficSigns"),
1397 class_<PrimitiveLayer<Area>, boost::noncopyable>(
"PrimitiveLayerArea", no_init);
1398 class_<PrimitiveLayer<Lanelet>, boost::noncopyable>(
"PrimitiveLayerLanelet", no_init);
1400 wrapLayer<AreaLayer, bases<PrimitiveLayer<Area>>>(
"AreaLayer")
1403 "Find areas with this regulatory element")
1406 "Find areas with this linestring");
1407 wrapLayer<LaneletLayer, bases<PrimitiveLayer<Lanelet>>>(
"LaneletLayer")
1410 "Find lanelets with this regualtory element")
1413 "Lanelets with this linestring");
1414 wrapLayer<PolygonLayer>(
"PolygonLayer")
1417 "Find polygons with this point");
1418 wrapLayer<LineStringLayer>(
"LineStringLayer")
1421 "Find linestrings with this point");
1422 wrapLayer<PointLayer>(
"PointLayer");
1423 wrapLayer<RegulatoryElementLayer>(
"RegulatoryElementLayer");
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)")
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)");
1440 class_<LaneletMap, bases<LaneletMapLayers>,
LaneletMapPtr, boost::noncopyable>(
1442 "A lanelet map collects lanelet primitives. It can be used for writing and loading and creating routing "
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 "
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 "
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 "
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 "
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>();
1468 class_<LaneletSubmap, bases<LaneletMapLayers>,
LaneletSubmapPtr, boost::noncopyable>(
1470 "A submap manages parts of a lanelet map. An important difference is that adding an object to the map will "
1472 "add its subobjects too, making it more efficient to create. Apart from that, it offers a similar "
1474 "compared to a lanelet map.",
1475 init<>(
"Create an empty lanelet submap"))
1478 "Create a lanelet map of this submap that also holds all subobjects. This is a potentially costly "
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 "
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 "
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 "
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 "
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 "
1497 register_ptr_to_python<LaneletSubmapConstPtr>();
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)");
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");
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");