Skip to content

Commit

Permalink
Add python repr for routing module
Browse files Browse the repository at this point in the history
  • Loading branch information
poggenhans committed Jan 25, 2025
1 parent 7afad88 commit 01ac3ef
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 9 deletions.
12 changes: 6 additions & 6 deletions lanelet2_python/python_api/core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ std::string repr(const RegulatoryElementConstPtrs& regelems) {
}

template <typename LaneletT>
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()));
Expand All @@ -54,7 +54,7 @@ std::string makeLaneletRepr(const std::string& displayName, bool withRegelems, c
}

template <typename AreaT>
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()));
Expand Down Expand Up @@ -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<LineString2d>());
Expand Down Expand Up @@ -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<LineString3d>())
Expand Down Expand Up @@ -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<Polygon2d>())
.def(IsPrimitive<Polygon2d>());

Expand All @@ -941,7 +941,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
init<Id, Points3d, AttributeMap>((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<Polygon3d>())
.def(IsPrimitive<Polygon3d>());

Expand Down
14 changes: 13 additions & 1 deletion lanelet2_python/python_api/routing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <boost/make_shared.hpp>

#include "lanelet2_python/internal/converter.h"
#include "lanelet2_python/internal/repr.h"

using namespace boost::python;
using namespace lanelet;
Expand Down Expand Up @@ -55,6 +56,7 @@ Optional<T> 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;
Expand Down Expand Up @@ -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

Expand Down Expand Up @@ -280,7 +287,11 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT

class_<LaneletRelation>("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>("RelationType")
.value("Successor", RelationType::Successor)
Expand Down Expand Up @@ -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");
}
4 changes: 2 additions & 2 deletions lanelet2_python/test/test_lanelet2.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down

0 comments on commit 01ac3ef

Please sign in to comment.