diff --git a/lanelet2_python/include/lanelet2_python/internal/repr.h b/lanelet2_python/include/lanelet2_python/internal/repr.h new file mode 100644 index 00000000..979bcd32 --- /dev/null +++ b/lanelet2_python/include/lanelet2_python/internal/repr.h @@ -0,0 +1,51 @@ +#pragma once +#include +#include +#include + +namespace lanelet { +namespace python { +inline void formatHelper(std::ostream& os) {} + +template +// NOLINTNEXTLINE(readability-identifier-naming) +void formatHelper(std::ostream& os, const std::string& s, const Args&... Args_) { + if (!s.empty()) { + os << ", "; + } + os << s; + formatHelper(os, Args_...); +} + +template +// NOLINTNEXTLINE(readability-identifier-naming) +void formatHelper(std::ostream& os, const T& next, const Args&... Args_) { + os << ", "; + os << next; + formatHelper(os, Args_...); +} + +template +// NOLINTNEXTLINE(readability-identifier-naming) +void format(std::ostream& os, const T& first, const Args&... Args_) { + os << first; + formatHelper(os, Args_...); +} + +template +// NOLINTNEXTLINE(readability-identifier-naming) +std::string makeRepr(const char* name, const Args&... Args_) { + std::ostringstream os; + os << name << '('; + format(os, Args_...); + os << ')'; + return os.str(); +} + +inline std::string repr(const boost::python::object& o) { + using namespace boost::python; + object repr = import("builtins").attr("repr"); + return call(repr.ptr(), o); +} +} // namespace python +} // namespace lanelet \ No newline at end of file diff --git a/lanelet2_python/python_api/core.cpp b/lanelet2_python/python_api/core.cpp index 54faea85..28e2d5f9 100644 --- a/lanelet2_python/python_api/core.cpp +++ b/lanelet2_python/python_api/core.cpp @@ -8,55 +8,86 @@ #include #include #include -#include -#include #include "lanelet2_core/Attribute.h" #include "lanelet2_core/Forward.h" #include "lanelet2_core/primitives/Area.h" #include "lanelet2_python/internal/converter.h" +#include "lanelet2_python/internal/repr.h" using namespace boost::python; using namespace lanelet; -namespace { -void formatHelper(std::ostream& os) {} +namespace lanelet { +namespace python { +class ReprWrapper { + public: + ReprWrapper(const std::string& text) : text_(text) {} + std::string operator()() const { return text_; } -template -// NOLINTNEXTLINE(readability-identifier-naming) -void formatHelper(std::ostream& os, const std::string& s, const Args&... Args_) { - if (!s.empty()) { - os << ", "; + private: + std::string text_; +}; + +std::string repr(const AttributeMap& a) { + if (a.empty()) { + return {}; } - os << s; - formatHelper(os, Args_...); + return repr(object(a)); } -template -// NOLINTNEXTLINE(readability-identifier-naming) -void formatHelper(std::ostream& os, const T& next, const Args&... Args_) { - os << ", "; - os << next; - formatHelper(os, Args_...); +std::string repr(const RegulatoryElementConstPtrs& regelems) { + if (regelems.empty()) { + return {}; + } + return repr(list(regelems)); } -template -// NOLINTNEXTLINE(readability-identifier-naming) -void format(std::ostream& os, const T& first, const Args&... Args_) { - os << first; - formatHelper(os, Args_...); +template +std::string makeLaneletRepr(const std::string& displayName, bool withRegelems, const LaneletT& llt) { + if (withRegelems) { + return makeRepr("Lanelet", llt.id(), repr(object(llt.leftBound())), repr(object(llt.rightBound())), + repr(llt.attributes()), repr(ConstLanelet(llt).regulatoryElements())); + } + return makeRepr("Lanelet", llt.id(), repr(object(llt.leftBound())), repr(object(llt.rightBound())), + repr(llt.attributes())); } -template -// NOLINTNEXTLINE(readability-identifier-naming) -std::string makeRepr(const char* name, const Args&... Args_) { - std::ostringstream os; - os << name << '('; - format(os, Args_...); - os << ')'; - return os.str(); +template +std::string makeAreaRepr(const std::string& displayName, bool withRegelems, const AreaT& area) { + if (withRegelems) { + return makeRepr("Area", area.id(), repr(object(area.outerBound())), repr(object(area.innerBounds())), + repr(area.attributes()), repr(ConstArea(area).regulatoryElements())); + } + return makeRepr("Area", area.id(), repr(object(area.outerBound())), repr(object(area.innerBounds())), + repr(area.attributes())); } +std::string repr(const RuleParameterMap& ruleParams) { + using namespace boost::python; + auto paramsDict = dict(ruleParams); + // this dict will be a dict of lists. If these contain lanelets/areas, we have to make sure they are printed without + // regulatory elements, otherwise we will create an infinite loop + auto values = paramsDict.values(); + for (int v = 0; v < len(values); ++v) { // NOLINT + list l = extract(values[v]); + for (int i = 0; i < len(l); ++i) { // NOLINT + if (extract(l[i]).check()) { + l[i] = ReprWrapper(makeLaneletRepr("Lanelet", false, extract(l[i])())); + } + if (extract(l[i]).check()) { + l[i] = ReprWrapper(makeAreaRepr("Area", false, extract(l[i])())); + } + } + } + return repr(paramsDict); +} + +} // namespace python +} // namespace lanelet + +namespace { + struct AttributeToPythonStr { static PyObject* convert(Attribute const& s) { return boost::python::incref(boost::python::object(s.value()).ptr()); } }; @@ -449,27 +480,14 @@ Optional objectToOptional(const object& o) { return o == object() ? Optional{} : Optional{extract(o)()}; } -std::string repr(const object& o) { - object repr = import("builtins").attr("repr"); - return call(repr.ptr(), o); -} - -std::string repr(const AttributeMap& a) { - if (a.empty()) { - return {}; - } - return repr(object(a)); -} - -std::string repr(const RegulatoryElementConstPtrs& regelems) { - if (regelems.empty()) { - return {}; - } - return repr(list(regelems)); -} } // namespace BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT + using namespace lanelet::python; + + class_("_ReprWrapper", "Internal helper class for repr", no_init) + .def("__repr__", &ReprWrapper::operator(), "Returns the string representation of this object"); + class_("BasicPoint2d", "A simple 2D point", init((arg("x") = 0., arg("y") = 0.))) .def(init<>("BasicPoint2d()")) .add_property("x", getXWrapper, setXWrapper, "x coordinate") @@ -677,21 +695,18 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT init<>("Create an empty attriute map")) .def(IsHybridMap()) .def(self_ns::str(self_ns::self)) - .def( - "__repr__", +[](const AttributeMap& a) { return makeRepr("AttributeMap", repr(dict(a))); }); + .def("__repr__", +[](const AttributeMap& a) { return makeRepr("AttributeMap", repr(dict(a))); }); class_("RuleParameterMap", "Used by RegulatoryElement. Works like a dictionary that maps roles (strings) to a list of " "primitives with that role (parameters).", init<>("Create empty rule parameter map")) .def(IsHybridMap()) - .def( - "__repr__", +[](const RuleParameterMap& r) { return makeRepr("RuleParameterMap", repr(dict(r))); }); + .def("__repr__", +[](const RuleParameterMap& r) { return makeRepr("RuleParameterMap", repr(dict(r))); }); class_("ConstRuleParameterMap", init<>("ConstRuleParameterMap()")) .def(IsHybridMap()) - .def( - "__repr__", +[](const RuleParameterMap& r) { return makeRepr("RuleParameterMap", repr(dict(r))); }); + .def("__repr__", +[](const ConstRuleParameterMap& r) { return makeRepr("ConstRuleParameterMap", repr(dict(r))); }); class_("ConstPoint2d", "Immutable 2D point primitive. It can not be instanciated from python but is returned from a " @@ -701,7 +716,8 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .add_property("x", getXWrapper, "x coordinate") .add_property("y", getYWrapper, "y coordinate") .def( - "__repr__", +[](const ConstPoint2d& p) { return makeRepr("ConstPoint2d", p.id(), p.x(), p.y(), repr(p.attributes())); }) + "__repr__", + +[](const ConstPoint2d& p) { return makeRepr("ConstPoint2d", p.id(), p.x(), p.y(), repr(p.attributes())); }) .def("basicPoint", &ConstPoint2d::basicPoint, return_internal_reference<>(), "Returns a plain 2D point primitive (no ID, no attributes) for efficient geometry operations"); class_>( @@ -763,8 +779,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def_readwrite("lon", &GPSPoint::lon, "Longitude according to WGS84") .def_readwrite("alt", &GPSPoint::ele, "DEPRECATED: Elevation according to WGS84 [m]. Use ele instead.") .def_readwrite("ele", &GPSPoint::ele, "Elevation according to WGS84 [m]") - .def( - "__repr__", +[](const GPSPoint& p) { return makeRepr("GPSPoint", p.lat, p.lon, p.ele); }); + .def("__repr__", +[](const GPSPoint& p) { return makeRepr("GPSPoint", p.lat, p.lon, p.ele); }); class_( "ConstLineString2d", @@ -1018,11 +1033,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("inverted", &ConstLanelet::inverted, "Returns whether this lanelet has been inverted") .def("polygon2d", &ConstLanelet::polygon2d, "Outline of this lanelet as 2D polygon") .def("polygon3d", &ConstLanelet::polygon3d, "Outline of this lanelet as 3D polygon") - .def( - "__repr__", +[](Lanelet& llt) { - return makeRepr("Lanelet", llt.id(), repr(object(llt.leftBound())), repr(object(llt.rightBound())), - repr(llt.attributes()), repr(ConstLanelet(llt).regulatoryElements())); - }); + .def("__repr__", +[](Lanelet& llt) { return makeLaneletRepr("Lanelet", true, llt); }); class_("LaneletSequence", "A combined lane formed from multiple lanelets", init()) .add_property("centerline", &LaneletSequence::centerline, "Centerline of the combined lanelets") @@ -1080,8 +1091,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__iter__", iterator()) .def("__len__", &InnerBounds::size, "Number of holes") .def("__getitem__", wrappers::getItem, return_value_policy()) - .def( - "__repr__", +[](const ConstInnerBounds& b) { return repr(list(b)); }); + .def("__repr__", +[](const ConstInnerBounds& b) { return repr(list(b)); }); class_("InnerBounds", "A list-like type to hold of inner boundaries of an Area", no_init) .def("__setitem__", wrappers::setItem) @@ -1092,8 +1102,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__iter__", iterator()) .def("__len__", &InnerBounds::size, "Number of holes") .def("__getitem__", wrappers::getItem, return_value_policy()) - .def( - "__repr__", +[](const InnerBounds& b) { return repr(list(b)); }); + .def("__repr__", +[](const InnerBounds& b) { return repr(list(b)); }); class_( "ConstArea", @@ -1121,11 +1130,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "DEPRECATED. Using it throws an exception. Use innerBoundPolygons instead!") .def("innerBoundPolygons", &ConstArea::innerBoundPolygons, "Returns the inner boundaries as a list of CompoundPolygon3d") - .def( - "__repr__", +[](const ConstArea& ar) { - return makeRepr("ConstArea", ar.id(), repr(list(ar.outerBound())), repr(object(ar.innerBounds())), - repr(ar.attributes()), repr(ar.regulatoryElements())); - }); + .def("__repr__", +[](const ConstArea& ar) { return makeAreaRepr("ConstArea", true, ar); }); class_>( "Area", "Represents an area, potentially with holes, in the map", @@ -1152,13 +1157,12 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("removeRegulatoryElement", &Area::removeRegulatoryElement, "Removes a regulatory element, retunrs true on success", arg("regelem")) .def("outerBoundPolygon", &Area::outerBoundPolygon, "Returns the outer boundary as a CompoundPolygon3d") - .def("innerBoundPolygon", +[](const Area& /*ar*/) { throw std::runtime_error("innerBoundPolygon is deprecated. Use innerBoundPolygons instead!");}, "DEPRECATED. Using it throws an exception. Use innerBoundPolygons instead!") + .def("innerBoundPolygon", +[](const Area& /*ar*/) { + throw std::runtime_error("innerBoundPolygon is deprecated. Use innerBoundPolygons instead!");}, "DEPRECATED. Using it throws an exception. Use innerBoundPolygons instead!") .def("innerBoundPolygons", &Area::innerBoundPolygons, "Returns the inner boundaries as a list of CompoundPolygon3d") .def( - "__repr__", +[](Area& ar) { - return makeRepr("Area", ar.id(), repr(list(ar.outerBound())), repr(object(ar.innerBounds())), - repr(ar.attributes()), repr(ConstArea(ar).regulatoryElements())); + "__repr__", +[](Area& ar) { return makeAreaRepr("Area", true, ar); }); using GetParamSig = ConstRuleParameterMap (RegulatoryElement::*)() const; @@ -1179,7 +1183,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .def("__len__", &RegulatoryElement::size) .def( "__repr__", +[](RegulatoryElement& r) { - return makeRepr("RegulatoryElement", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes())); + return makeRepr("RegulatoryElement", r.id(), repr(r.constData()->parameters), repr(r.attributes())); }); register_ptr_to_python(); @@ -1191,7 +1195,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT .add_property( "stopLine", +[](TrafficLight& self) { return self.stopLine(); }, &TrafficLight::setStopLine, "The stop line of for this TrafficLight (a LineString or None)") - .add_property("removeStopLine", &TrafficLight::removeStopLine, "Clear the stop line") + .def("removeStopLine", &TrafficLight::removeStopLine, "Clear the stop line") .add_property( "trafficLights", +[](TrafficLight& self) { return self.trafficLights(); }, "Traffic lights. Should all have the same phase.") @@ -1202,7 +1206,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Removes a given traffic light, returns true on success") .def( "__repr__", +[](TrafficLight& r) { - return makeRepr("TrafficLight", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes())); + return makeRepr("TrafficLight", r.id(), repr(r.constData()->parameters), repr(r.attributes())); }); implicitly_convertible, RegulatoryElementPtr>(); @@ -1241,7 +1245,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Removes the yielding lanelet, returns true on success.") .def( "__repr__", +[](RightOfWay& r) { - return makeRepr("RightOfWay", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes())); + return makeRepr("RightOfWay", r.id(), repr(r.constData()->parameters), repr(r.attributes())); }); implicitly_convertible, RegulatoryElementPtr>(); @@ -1273,7 +1277,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Removes a lanelet from the all way stop, returns True on success.") .def( "__repr__", +[](AllWayStop& r) { - return makeRepr("AllWayStop", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes())); + return makeRepr("AllWayStop", r.id(), repr(r.constData()->parameters), repr(r.attributes())); }); implicitly_convertible, RegulatoryElementPtr>(); @@ -1335,7 +1339,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Returns types of the cancelling traffic signs (a list of strings) if it exists.") .def( "__repr__", +[](TrafficSign& r) { - return makeRepr("TrafficSign", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes())); + return makeRepr("TrafficSign", r.id(), repr(r.constData()->parameters), repr(r.attributes())); }); implicitly_convertible, RegulatoryElementPtr>(); @@ -1351,7 +1355,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT arg("refLines") = LineStrings3d(), arg("cancelLines") = LineStrings3d()))) .def( "__repr__", +[](SpeedLimit& r) { - return makeRepr("SpeedLimit", r.id(), repr(dict(r.constData()->parameters)), repr(r.attributes())); + return makeRepr("SpeedLimit", r.id(), repr(r.constData()->parameters), repr(r.attributes())); }); class_, boost::noncopyable>("PrimitiveLayerArea", no_init); // NOLINT diff --git a/lanelet2_python/test/test_lanelet2.py b/lanelet2_python/test/test_lanelet2.py index df13c236..fd97d58c 100644 --- a/lanelet2_python/test/test_lanelet2.py +++ b/lanelet2_python/test/test_lanelet2.py @@ -1,6 +1,6 @@ import unittest import lanelet2 # if we fail here, there is something wrong with registration -from lanelet2.core import AttributeMap, getId, BasicPoint2d, Point3d, LineString3d, Lanelet, RegulatoryElement, TrafficLight, LaneletMap, createMapFromLanelets +from lanelet2.core import AttributeMap, getId, BasicPoint2d, Point3d, LineString3d, Lanelet, RegulatoryElement, RightOfWay, TrafficLight, LaneletMap, createMapFromLanelets from lanelet2.geometry import distance, intersects2d, boundingBox2d, to2D, intersection @@ -30,12 +30,12 @@ def getLaneletMap(): return createMapFromLanelets([lanelet]) -def checkPrimitiveId(testClass, primitive): +def checkPrimitiveId(testClass: unittest.TestCase, primitive: Lanelet): primitive.id = 30 testClass.assertEqual(primitive.id, 30) -def checkPrimitiveAttributes(testClass, primitive): +def checkPrimitiveAttributes(testClass: unittest.TestCase, primitive: Lanelet): lenBefore = len(primitive.attributes) primitive.attributes["newkey"] = "newvalue" testClass.assertEqual(lenBefore + 1, len(primitive.attributes)) @@ -65,6 +65,22 @@ def test_lanelet_regelem(self): self.assertEqual(len(llt.trafficLights()), 1) self.assertEqual(len(llt.trafficSigns()), 0) self.assertEqual(len(llt.regulatoryElements), 1) + + def test_lanelet_repr(self): + llt = getLanelet() + llt_from_repr = eval(repr(llt)) + self.assertEqual(llt.id, llt_from_repr.id) + self.assertEqual(llt.leftBound.id, llt_from_repr.leftBound.id) + self.assertEqual(llt.rightBound.id, llt_from_repr.rightBound.id) + self.assertEqual(llt.attributes, llt_from_repr.attributes) + + def test_lanelet_repr_regelem_cycle(self): + llt = getLanelet() + llt2 = getLanelet() + regelem = RightOfWay(getId(), AttributeMap(), [llt], [llt2]) + llt.addRegulatoryElement(regelem) + self.assertIn("Lanelet(id=0,", repr(llt)) + self.assertIn(f"RightOfWay(id={regelem.id},", repr(regelem)) class LaneletMapApiTestCase(unittest.TestCase):