Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add pyi stub files for python interface #385

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 19 additions & 17 deletions lanelet2_examples/scripts/tutorial.py
Original file line number Diff line number Diff line change
Expand Up @@ -162,38 +162,39 @@ def part4reading_and_writing():
map.add(lanelet)
path = os.path.join(tempfile.mkdtemp(), 'mapfile.osm')
# Select a suitable projector depending on the data source
## UtmProjector: (0,0,0) is at the provided lat/lon on the WGS84 ellipsoid
# UtmProjector: (0,0,0) is at the provided lat/lon on the WGS84 ellipsoid
projector = UtmProjector(lanelet2.io.Origin(49, 8.4))
## MarcatorProjector: (0,0,0) is at the provided lat/lon on the mercator cylinder
# MarcatorProjector: (0,0,0) is at the provided lat/lon on the mercator cylinder
projector = MercatorProjector(lanelet2.io.Origin(49, 8.4))
## LocalCartesianProjector: (0,0,0) is at the provided origin (including elevation)
# LocalCartesianProjector: (0,0,0) is at the provided origin (including elevation)
projector = LocalCartesianProjector(lanelet2.io.Origin(49, 8.4, 123))

# Writing the map to a file
## 1. Write with the given projector and use default parameters
# 1. Write with the given projector and use default parameters
lanelet2.io.write(path, map, projector)

## 2. Write and get the possible errors
# 2. Write and get the possible errors
write_errors = lanelet2.io.writeRobust(path, map, projector)
assert not write_errors

## 3. Write using the default spherical mercator projector at the giver origin
## This was the default projection in Lanelet1. Use is not recommended.
# 3. Write using the default spherical mercator projector at the giver origin
# This was the default projection in Lanelet1. Use is not recommended.
lanelet2.io.write(path, map, lanelet2.io.Origin(49, 8.4))

## 4. Write using the given projector and override the default values of the optional parameters for JOSM
# 4. Write using the given projector and override the default values of the optional parameters for JOSM
params = {
"josm_upload": "true", # value for the attribute "upload", default is "false"
"josm_format_elevation": "true" # whether to limit up to 2 decimals, default is the same as for lat/lon
};
"josm_upload": "true", # value for the attribute "upload", default is "false"
# whether to limit up to 2 decimals, default is the same as for lat/lon
"josm_format_elevation": "true"
}
lanelet2.io.write(path, map, projector, params)

# Loading the map from a file
loadedMap, load_errors = lanelet2.io.loadRobust(path, projector)
assert not load_errors
assert loadedMap.laneletLayer.exists(lanelet.id)

## GeocentricProjector: the origin is the centre of the Earth
# GeocentricProjector: the origin is the centre of the Earth
gc_projector = GeocentricProjector()
write_errors = lanelet2.io.writeRobust(path, map, gc_projector)
assert not write_errors
Expand Down Expand Up @@ -228,6 +229,7 @@ def part6routing():
# here we query a route through the lanelets and get all the vehicle lanelets that conflict with the shortest path
# in that route
route = graph.getRoute(lanelet, toLanelet)
assert route
path = route.shortestPath()
confLlts = [llt for llt in route.allConflictingInMap() if llt not in path]
assert len(confLlts) > 0
Expand All @@ -236,11 +238,11 @@ def part6routing():
assert hasPathFromTo(graph, lanelet, toLanelet)


def hasPathFromTo(graph, start, target):
def hasPathFromTo(graph: lanelet2.routing.RoutingGraph, start: lanelet2.core.Lanelet, target: lanelet2.core.Lanelet):
class TargetFound(BaseException):
pass

def raiseIfDestination(visitInformation):
def raiseIfDestination(visitInformation: lanelet2.routing.LaneletVisitInformation):
# this function is called for every successor of lanelet with a LaneletVisitInformation object.
# if the function returns true, the search continues with the successors of this lanelet.
# Otherwise, the followers will not be visited through this lanelet, but could still be visited through
Expand All @@ -256,15 +258,15 @@ def raiseIfDestination(visitInformation):
return True


def get_linestring_at_x(x):
def get_linestring_at_x(x: float):
return LineString3d(getId(), [Point3d(getId(), x, i, 0) for i in range(0, 3)])


def get_linestring_at_y(y):
def get_linestring_at_y(y: float):
return LineString3d(getId(), [Point3d(getId(), i, y, 0) for i in range(0, 3)])


def get_a_lanelet(index=0):
def get_a_lanelet(index: int = 0):
return Lanelet(getId(),
get_linestring_at_y(2+index),
get_linestring_at_y(0+index))
Expand Down
3 changes: 3 additions & 0 deletions lanelet2_python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,9 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC)
mrt_add_python_api( lanelet2
FILES ${PROJECT_PYTHON_SOURCE_FILES_SRC}
)
_mrt_get_python_destination(PROJECT_PYTHON_DESTINATION)
mrt_glob_files(PROJECT_PYTHON_STUBS "typings/lanelet2/*.pyi")
install(FILES ${PROJECT_PYTHON_STUBS} DESTINATION ${PROJECT_PYTHON_DESTINATION}/lanelet2)
endif()

############################
Expand Down
34 changes: 34 additions & 0 deletions lanelet2_python/python_api/core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,21 @@
#include "lanelet2_core/Attribute.h"
#include "lanelet2_core/Forward.h"
#include "lanelet2_core/primitives/Area.h"
#include "lanelet2_core/primitives/Polygon.h"
#include "lanelet2_core/primitives/Primitive.h"
#include "lanelet2_python/internal/converter.h"

using namespace boost::python;
using namespace lanelet;

// std::hash is not defined for ConstHybridPolygon2d/3d, so we need to define it ourselves
namespace std {
template <>
struct hash<lanelet::ConstHybridPolygon2d> : public lanelet::HashBase<lanelet::ConstHybridPolygon2d> {};
template <>
struct hash<lanelet::ConstHybridPolygon3d> : public lanelet::HashBase<lanelet::ConstHybridPolygon3d> {};
} // namespace std

namespace {
void formatHelper(std::ostream& os) {}

Expand Down Expand Up @@ -944,6 +954,30 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
.def("lineStrings", &CompoundPolygon3d::lineStrings, "The linestrings in this polygon")
.def("ids", &CompoundPolygon3d::ids, "List of the ids of the linestrings");

class_<ConstHybridPolygon2d>("ConstHybridPolygon2d",
"A 2D Polygon that behaves like a normal BasicPolygon (i.e. returns BasicPoints), "
"but still has an ID and attributes.",
init<ConstPolygon2d>(arg("polygon"), "Create from a 2D polygon"))
.def(
"__repr__",
+[](const ConstHybridPolygon2d& p) {
return makeRepr("ConstHybridPolygon2d", p.id(), repr(list(p)), repr(p.attributes()));
})
.def(IsConstLineString<ConstHybridPolygon2d, false>())
.def(IsConstPrimitive<ConstHybridPolygon2d>());

class_<ConstHybridPolygon3d>("ConstHybridPolygon3d",
"A 3D Polygon that behaves like a normal BasicPolygon (i.e. returns BasicPoints), "
"but still has an ID and attributes.",
init<ConstPolygon3d>(arg("polygon"), "Create from a 3D polygon"))
.def(
"__repr__",
+[](const ConstHybridPolygon3d& p) {
return makeRepr("ConstHybridPolygon3d", p.id(), repr(list(p)), repr(p.attributes()));
})
.def(IsConstLineString<ConstHybridPolygon3d, false>())
.def(IsConstPrimitive<ConstHybridPolygon3d>());

class_<ConstLanelet>(
"ConstLanelet",
"An immutable lanelet primitive. Consist of a left and right boundary, attributes and a set of "
Expand Down
9 changes: 3 additions & 6 deletions lanelet2_python/python_api/geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <boost/geometry/algorithms/intersection.hpp>
#include <boost/geometry/geometries/register/multi_linestring.hpp>

#include "lanelet2_core/primitives/CompoundPolygon.h"
#include "lanelet2_python/internal/converter.h"

BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::LineStrings2d)
Expand Down Expand Up @@ -96,6 +97,7 @@ object to2D(object o) {
TO2D_AS(Polygon3d)
TO2D_AS(ConstPolygon3d)
TO2D_AS(CompoundLineString3d)
TO2D_AS(CompoundPolygon3d)
return o;
}

Expand All @@ -110,6 +112,7 @@ object to3D(object o) {
TO3D_AS(Polygon2d)
TO3D_AS(ConstPolygon2d)
TO3D_AS(CompoundLineString2d)
TO3D_AS(CompoundPolygon2d)
return o;
}
#undef TO2D_AS
Expand Down Expand Up @@ -193,8 +196,6 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
"distance", +[](const ConstLanelet& llt1, const ConstLanelet& llt2) { return lg::distance2d(llt1, llt2); });
def(
"distance", +[](const BasicPoint2d& p, const ConstLanelet& llt) { return lg::distance2d(llt, p); });
def(
"distance", +[](const ConstLanelet& llt2, const ConstLanelet& llt1) { return lg::distance2d(llt1, llt2); });

// p2area
def(
Expand All @@ -216,14 +217,10 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
def("distance", lg::distance<CompoundLineString3d, ConstPoint3d>);
def("distance", lg::distance<ConstPoint3d, ConstLineString3d>);
def("distance", lg::distance<ConstLineString3d, ConstPoint3d>);
def("distance", lg::distance<ConstPoint3d, CompoundLineString3d>);
def("distance", lg::distance<CompoundLineString3d, ConstPoint3d>);

// p2lines
def("distanceToLines", distancePointToLss<ConstPoint2d>);
def("distanceToLines", distancePointToLss<BasicPoint2d>);
def("distanceToLines", distancePointToLss<ConstPoint2d>);
def("distanceToLines", distancePointToLss<BasicPoint2d>);

// l2l
def(
Expand Down
4 changes: 2 additions & 2 deletions lanelet2_python/python_api/traffic_rules.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
auto core = import("lanelet2.core");

class_<SpeedLimitInformation>("SpeedLimitInformation", "Current speed limit as returned by a traffic rule object")
.def("__init__", makeSpeedLimit,
.def("__init__", makeSpeedLimit, (arg("speedLimitMPS"), arg("isMandatory") = true),
"Initialize from speed limit [m/s] and bool if speedlimit is "
"mandatory")
.add_property("speedLimit", getVelocity, setVelocity, "velocity in km/h")
Expand Down Expand Up @@ -102,7 +102,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
.add_static_property("Pedestrian", asString<Participants::Pedestrian>)
.add_static_property("Train", asString<Participants::Train>);

def("create", createTrafficRulesWrapper,
def("create", createTrafficRulesWrapper, (arg("location"), arg("participant")),
"Create a traffic rules object from location and participant string (see "
"Locations and Participants class");
}
6 changes: 3 additions & 3 deletions lanelet2_python/test/test_lanelet2_projection.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ def test_UtmProjector(self):
gps_point = utm_projector.reverse(utm_point)
self.assertEqual(round(gps_point.lat, 5), self.origin_lat)
self.assertEqual(round(gps_point.lon, 5), self.origin_lon)
self.assertEqual(round(gps_point.alt, 5), self.origin_ele)
self.assertEqual(round(gps_point.ele, 5), self.origin_ele)

def test_LocalCartesianProjector(self):
# NOTE: the projected plane is tangential to the WGS84 ellipsoid
Expand All @@ -54,7 +54,7 @@ def test_LocalCartesianProjector(self):
gps_point = local_cartesian_projector.reverse(local_cartesian_point)
self.assertEqual(round(gps_point.lat, self.decimals), self.origin_lat)
self.assertEqual(round(gps_point.lon, self.decimals), self.origin_lon)
self.assertEqual(round(gps_point.alt, self.decimals), self.origin_ele)
self.assertEqual(round(gps_point.ele, self.decimals), self.origin_ele)

def test_GeocentricProjector(self):
geocentric_projector = GeocentricProjector()
Expand All @@ -67,7 +67,7 @@ def test_GeocentricProjector(self):
gps_point = geocentric_projector.reverse(self.origin_ecef)
self.assertEqual(round(gps_point.lat, self.decimals), self.origin_lat)
self.assertEqual(round(gps_point.lon, self.decimals), self.origin_lon)
self.assertEqual(round(gps_point.alt, self.decimals), self.origin_ele)
self.assertEqual(round(gps_point.ele, self.decimals), self.origin_ele)


if __name__ == '__main__':
Expand Down
4 changes: 4 additions & 0 deletions lanelet2_python/typings/lanelet2/__init__.pyi
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
from lanelet2 import core, geometry, io, routing, traffic_rules, matching, projection

__all__ = ["core", "geometry", "io", "routing",
"traffic_rules", "matching", "projection"]
Loading