Skip to content

Commit 820436e

Browse files
authored
Add pyi stub files for python interface (#385)
1 parent c6445c9 commit 820436e

File tree

14 files changed

+3176
-28
lines changed

14 files changed

+3176
-28
lines changed

lanelet2_examples/scripts/tutorial.py

Lines changed: 19 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -162,38 +162,39 @@ def part4reading_and_writing():
162162
map.add(lanelet)
163163
path = os.path.join(tempfile.mkdtemp(), 'mapfile.osm')
164164
# Select a suitable projector depending on the data source
165-
## UtmProjector: (0,0,0) is at the provided lat/lon on the WGS84 ellipsoid
165+
# UtmProjector: (0,0,0) is at the provided lat/lon on the WGS84 ellipsoid
166166
projector = UtmProjector(lanelet2.io.Origin(49, 8.4))
167-
## MarcatorProjector: (0,0,0) is at the provided lat/lon on the mercator cylinder
167+
# MarcatorProjector: (0,0,0) is at the provided lat/lon on the mercator cylinder
168168
projector = MercatorProjector(lanelet2.io.Origin(49, 8.4))
169-
## LocalCartesianProjector: (0,0,0) is at the provided origin (including elevation)
169+
# LocalCartesianProjector: (0,0,0) is at the provided origin (including elevation)
170170
projector = LocalCartesianProjector(lanelet2.io.Origin(49, 8.4, 123))
171171

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

176-
## 2. Write and get the possible errors
176+
# 2. Write and get the possible errors
177177
write_errors = lanelet2.io.writeRobust(path, map, projector)
178178
assert not write_errors
179179

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

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

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

196-
## GeocentricProjector: the origin is the centre of the Earth
197+
# GeocentricProjector: the origin is the centre of the Earth
197198
gc_projector = GeocentricProjector()
198199
write_errors = lanelet2.io.writeRobust(path, map, gc_projector)
199200
assert not write_errors
@@ -228,6 +229,7 @@ def part6routing():
228229
# here we query a route through the lanelets and get all the vehicle lanelets that conflict with the shortest path
229230
# in that route
230231
route = graph.getRoute(lanelet, toLanelet)
232+
assert route
231233
path = route.shortestPath()
232234
confLlts = [llt for llt in route.allConflictingInMap() if llt not in path]
233235
assert len(confLlts) > 0
@@ -236,11 +238,11 @@ def part6routing():
236238
assert hasPathFromTo(graph, lanelet, toLanelet)
237239

238240

239-
def hasPathFromTo(graph, start, target):
241+
def hasPathFromTo(graph: lanelet2.routing.RoutingGraph, start: lanelet2.core.Lanelet, target: lanelet2.core.Lanelet):
240242
class TargetFound(BaseException):
241243
pass
242244

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

258260

259-
def get_linestring_at_x(x):
261+
def get_linestring_at_x(x: float):
260262
return LineString3d(getId(), [Point3d(getId(), x, i, 0) for i in range(0, 3)])
261263

262264

263-
def get_linestring_at_y(y):
265+
def get_linestring_at_y(y: float):
264266
return LineString3d(getId(), [Point3d(getId(), i, y, 0) for i in range(0, 3)])
265267

266268

267-
def get_a_lanelet(index=0):
269+
def get_a_lanelet(index: int = 0):
268270
return Lanelet(getId(),
269271
get_linestring_at_y(2+index),
270272
get_linestring_at_y(0+index))

lanelet2_python/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,9 @@ if (PROJECT_PYTHON_SOURCE_FILES_SRC)
3434
mrt_add_python_api( lanelet2
3535
FILES ${PROJECT_PYTHON_SOURCE_FILES_SRC}
3636
)
37+
_mrt_get_python_destination(PROJECT_PYTHON_DESTINATION)
38+
mrt_glob_files(PROJECT_PYTHON_STUBS "typings/lanelet2/*.pyi")
39+
install(FILES ${PROJECT_PYTHON_STUBS} DESTINATION ${PROJECT_PYTHON_DESTINATION}/lanelet2)
3740
endif()
3841

3942
############################

lanelet2_python/python_api/core.cpp

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,21 @@
1414
#include "lanelet2_core/Attribute.h"
1515
#include "lanelet2_core/Forward.h"
1616
#include "lanelet2_core/primitives/Area.h"
17+
#include "lanelet2_core/primitives/Polygon.h"
18+
#include "lanelet2_core/primitives/Primitive.h"
1719
#include "lanelet2_python/internal/converter.h"
1820

1921
using namespace boost::python;
2022
using namespace lanelet;
2123

24+
// std::hash is not defined for ConstHybridPolygon2d/3d, so we need to define it ourselves
25+
namespace std {
26+
template <>
27+
struct hash<lanelet::ConstHybridPolygon2d> : public lanelet::HashBase<lanelet::ConstHybridPolygon2d> {};
28+
template <>
29+
struct hash<lanelet::ConstHybridPolygon3d> : public lanelet::HashBase<lanelet::ConstHybridPolygon3d> {};
30+
} // namespace std
31+
2232
namespace {
2333
void formatHelper(std::ostream& os) {}
2434

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

957+
class_<ConstHybridPolygon2d>("ConstHybridPolygon2d",
958+
"A 2D Polygon that behaves like a normal BasicPolygon (i.e. returns BasicPoints), "
959+
"but still has an ID and attributes.",
960+
init<ConstPolygon2d>(arg("polygon"), "Create from a 2D polygon"))
961+
.def(
962+
"__repr__",
963+
+[](const ConstHybridPolygon2d& p) {
964+
return makeRepr("ConstHybridPolygon2d", p.id(), repr(list(p)), repr(p.attributes()));
965+
})
966+
.def(IsConstLineString<ConstHybridPolygon2d, false>())
967+
.def(IsConstPrimitive<ConstHybridPolygon2d>());
968+
969+
class_<ConstHybridPolygon3d>("ConstHybridPolygon3d",
970+
"A 3D Polygon that behaves like a normal BasicPolygon (i.e. returns BasicPoints), "
971+
"but still has an ID and attributes.",
972+
init<ConstPolygon3d>(arg("polygon"), "Create from a 3D polygon"))
973+
.def(
974+
"__repr__",
975+
+[](const ConstHybridPolygon3d& p) {
976+
return makeRepr("ConstHybridPolygon3d", p.id(), repr(list(p)), repr(p.attributes()));
977+
})
978+
.def(IsConstLineString<ConstHybridPolygon3d, false>())
979+
.def(IsConstPrimitive<ConstHybridPolygon3d>());
980+
947981
class_<ConstLanelet>(
948982
"ConstLanelet",
949983
"An immutable lanelet primitive. Consist of a left and right boundary, attributes and a set of "

lanelet2_python/python_api/geometry.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include <boost/geometry/algorithms/intersection.hpp>
1010
#include <boost/geometry/geometries/register/multi_linestring.hpp>
1111

12+
#include "lanelet2_core/primitives/CompoundPolygon.h"
1213
#include "lanelet2_python/internal/converter.h"
1314

1415
BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::LineStrings2d)
@@ -96,6 +97,7 @@ object to2D(object o) {
9697
TO2D_AS(Polygon3d)
9798
TO2D_AS(ConstPolygon3d)
9899
TO2D_AS(CompoundLineString3d)
100+
TO2D_AS(CompoundPolygon3d)
99101
return o;
100102
}
101103

@@ -110,6 +112,7 @@ object to3D(object o) {
110112
TO3D_AS(Polygon2d)
111113
TO3D_AS(ConstPolygon2d)
112114
TO3D_AS(CompoundLineString2d)
115+
TO3D_AS(CompoundPolygon2d)
113116
return o;
114117
}
115118
#undef TO2D_AS
@@ -193,8 +196,6 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
193196
"distance", +[](const ConstLanelet& llt1, const ConstLanelet& llt2) { return lg::distance2d(llt1, llt2); });
194197
def(
195198
"distance", +[](const BasicPoint2d& p, const ConstLanelet& llt) { return lg::distance2d(llt, p); });
196-
def(
197-
"distance", +[](const ConstLanelet& llt2, const ConstLanelet& llt1) { return lg::distance2d(llt1, llt2); });
198199

199200
// p2area
200201
def(
@@ -216,14 +217,10 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
216217
def("distance", lg::distance<CompoundLineString3d, ConstPoint3d>);
217218
def("distance", lg::distance<ConstPoint3d, ConstLineString3d>);
218219
def("distance", lg::distance<ConstLineString3d, ConstPoint3d>);
219-
def("distance", lg::distance<ConstPoint3d, CompoundLineString3d>);
220-
def("distance", lg::distance<CompoundLineString3d, ConstPoint3d>);
221220

222221
// p2lines
223222
def("distanceToLines", distancePointToLss<ConstPoint2d>);
224223
def("distanceToLines", distancePointToLss<BasicPoint2d>);
225-
def("distanceToLines", distancePointToLss<ConstPoint2d>);
226-
def("distanceToLines", distancePointToLss<BasicPoint2d>);
227224

228225
// l2l
229226
def(

lanelet2_python/python_api/traffic_rules.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
5454
auto core = import("lanelet2.core");
5555

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

105-
def("create", createTrafficRulesWrapper,
105+
def("create", createTrafficRulesWrapper, (arg("location"), arg("participant")),
106106
"Create a traffic rules object from location and participant string (see "
107107
"Locations and Participants class");
108108
}

lanelet2_python/test/test_lanelet2_projection.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ def test_UtmProjector(self):
3636
gps_point = utm_projector.reverse(utm_point)
3737
self.assertEqual(round(gps_point.lat, 5), self.origin_lat)
3838
self.assertEqual(round(gps_point.lon, 5), self.origin_lon)
39-
self.assertEqual(round(gps_point.alt, 5), self.origin_ele)
39+
self.assertEqual(round(gps_point.ele, 5), self.origin_ele)
4040

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

5959
def test_GeocentricProjector(self):
6060
geocentric_projector = GeocentricProjector()
@@ -67,7 +67,7 @@ def test_GeocentricProjector(self):
6767
gps_point = geocentric_projector.reverse(self.origin_ecef)
6868
self.assertEqual(round(gps_point.lat, self.decimals), self.origin_lat)
6969
self.assertEqual(round(gps_point.lon, self.decimals), self.origin_lon)
70-
self.assertEqual(round(gps_point.alt, self.decimals), self.origin_ele)
70+
self.assertEqual(round(gps_point.ele, self.decimals), self.origin_ele)
7171

7272

7373
if __name__ == '__main__':
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
from lanelet2 import core, geometry, io, routing, traffic_rules, matching, projection
2+
3+
__all__ = ["core", "geometry", "io", "routing",
4+
"traffic_rules", "matching", "projection"]

0 commit comments

Comments
 (0)