From 01ac3efa5e9fa7114e341cb011afc319feed4a4d Mon Sep 17 00:00:00 2001 From: Fabian Poggenhans <22795364+poggenhans@users.noreply.github.com> Date: Mon, 20 Jan 2025 21:23:30 +0100 Subject: [PATCH] Add python repr for routing module --- lanelet2_python/python_api/core.cpp | 12 ++++++------ lanelet2_python/python_api/routing.cpp | 14 +++++++++++++- lanelet2_python/test/test_lanelet2.py | 4 ++-- 3 files changed, 21 insertions(+), 9 deletions(-) diff --git a/lanelet2_python/python_api/core.cpp b/lanelet2_python/python_api/core.cpp index 28e2d5f9..6ad66842 100644 --- a/lanelet2_python/python_api/core.cpp +++ b/lanelet2_python/python_api/core.cpp @@ -44,7 +44,7 @@ std::string repr(const RegulatoryElementConstPtrs& regelems) { } template -std::string makeLaneletRepr(const std::string& displayName, bool withRegelems, const LaneletT& llt) { +std::string makeLaneletRepr(const std::string& displayName, bool withRegelems, LaneletT& llt) { if (withRegelems) { return makeRepr("Lanelet", llt.id(), repr(object(llt.leftBound())), repr(object(llt.rightBound())), repr(llt.attributes()), repr(ConstLanelet(llt).regulatoryElements())); @@ -54,7 +54,7 @@ std::string makeLaneletRepr(const std::string& displayName, bool withRegelems, c } template -std::string makeAreaRepr(const std::string& displayName, bool withRegelems, const AreaT& area) { +std::string makeAreaRepr(const std::string& displayName, bool withRegelems, AreaT& area) { if (withRegelems) { return makeRepr("Area", area.id(), repr(object(area.outerBound())), repr(object(area.innerBounds())), repr(area.attributes()), repr(ConstArea(area).regulatoryElements())); @@ -813,7 +813,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "returned in reversed order") .def( "__repr__", - +[](const LineString2d& ls) { + +[](LineString2d& ls) { return makeRepr("LineString2d", ls.id(), repr(list(ls)), repr(ls.attributes())); }) .def(IsLineString()); @@ -849,7 +849,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "points returned in reversed order") .def( "__repr__", - +[](const LineString3d& ls) { + +[](LineString3d& ls) { return makeRepr("LineString3d", ls.id(), repr(list(ls)), repr(ls.attributes())); }) .def(IsLineString()) @@ -931,7 +931,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "Create from an ID, the boundary points and (optionally) attributes")) .def( "__repr__", - +[](const Polygon2d& p) { return makeRepr("Polygon2d", p.id(), repr(list(p)), repr(p.attributes())); }) + +[](Polygon2d& p) { return makeRepr("Polygon2d", p.id(), repr(list(p)), repr(p.attributes())); }) .def(IsLineString()) .def(IsPrimitive()); @@ -941,7 +941,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT init((arg("id"), arg("points"), arg("attributes") = AttributeMap()))) .def( "__repr__", - +[](const Polygon3d& p) { return makeRepr("Polygon3d", p.id(), repr(list(p)), repr(p.attributes())); }) + +[](Polygon3d& p) { return makeRepr("Polygon3d", p.id(), repr(list(p)), repr(p.attributes())); }) .def(IsLineString()) .def(IsPrimitive()); diff --git a/lanelet2_python/python_api/routing.cpp b/lanelet2_python/python_api/routing.cpp index f159a242..390609c6 100644 --- a/lanelet2_python/python_api/routing.cpp +++ b/lanelet2_python/python_api/routing.cpp @@ -4,6 +4,7 @@ #include #include "lanelet2_python/internal/converter.h" +#include "lanelet2_python/internal/repr.h" using namespace boost::python; using namespace lanelet; @@ -55,6 +56,7 @@ Optional objectToOptional(const object& o) { BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT auto trafficRules = import("lanelet2.traffic_rules"); using namespace lanelet::routing; + using namespace lanelet::python; using converters::IterableConverter; using converters::OptionalConverter; @@ -115,6 +117,11 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT "getRemainingLane", +[](const LaneletPath& self, const ConstLanelet& llt) { return self.getRemainingLane(llt); }, "get the sequence of remaining lanelets without a lane change") + .def( + "__repr__", + +[](const LaneletPath& self) { + return makeRepr("LaneletPath", repr(list(ConstLanelets{self.begin(), self.end()}))); + }) .def(self == self) // NOLINT .def(self != self); // NOLINT @@ -280,7 +287,11 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT class_("LaneletRelation") .def_readwrite("lanelet", &LaneletRelation::lanelet) - .def_readwrite("relationType", &LaneletRelation::relationType); + .def_readwrite("relationType", &LaneletRelation::relationType) + .def( + "__repr__", +[](const LaneletRelation& self) { + return makeRepr("LaneletRelation", repr(object(self.lanelet)), repr(object(self.relationType))); + }); enum_("RelationType") .value("Successor", RelationType::Successor) @@ -332,5 +343,6 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT +[](Route& self, const ConstLanelet& from, object func) { self.forEachPredecessor(from, std::move(func)); }, "similar to forEachSuccessor but instead goes backwards along the routing graph", (arg("lanelet"), arg("func"))) + .def("__contains__", &Route::contains, "Checks if a specific lanelet is part of the route", (arg("lanelet"))) .def("checkValidity", &Route::checkValidity, "perform sanity check on the route"); } diff --git a/lanelet2_python/test/test_lanelet2.py b/lanelet2_python/test/test_lanelet2.py index fd97d58c..dc702574 100644 --- a/lanelet2_python/test/test_lanelet2.py +++ b/lanelet2_python/test/test_lanelet2.py @@ -79,8 +79,8 @@ def test_lanelet_repr_regelem_cycle(self): 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)) + self.assertIn(f"Lanelet({llt.id}", repr(llt)) + self.assertIn(f"RightOfWay({regelem.id},", repr(regelem)) class LaneletMapApiTestCase(unittest.TestCase):