2 #include <lanelet2_core/geometry/Area.h>
3 #include <lanelet2_core/geometry/Lanelet.h>
4 #include <lanelet2_core/geometry/LaneletMap.h>
5 #include <lanelet2_core/geometry/LineString.h>
6 #include <lanelet2_core/geometry/Polygon.h>
7 #include <lanelet2_core/geometry/RegulatoryElement.h>
9 #include <boost/geometry/algorithms/intersection.hpp>
10 #include <boost/geometry/geometries/register/multi_linestring.hpp>
20 using namespace boost::python;
26 template <
typename PrimT>
28 using ResultT = std::vector<std::pair<double, PrimT>>;
33 return def(
"findNearest", func);
35 template <
typename PrimT,
typename GeometryT>
37 using ResultT = std::vector<std::pair<double, PrimT>>;
40 return def(
"findWithin2d", func, (arg(
"layer"), arg(
"geometry"), arg(
"maxDist") = 0),
41 "returns all elements that are closer than maxDist to a geometry in 2d");
43 template <
typename PrimT,
typename GeometryT>
45 using ResultT = std::vector<std::pair<double, PrimT>>;
48 return def(
"findWithin3d", func, (arg(
"layer"), arg(
"geometry"), arg(
"maxDist") = 0),
49 "returns all elements that are closer than maxDist to a geometry in 3d");
53 return utils::transform(pts, [](
auto&
p) {
return BasicPoint2d(
p.x(),
p.y()); });
68 if (extract<X>(o).check()) { \
69 return object(to2D(extract<X>(o)())); \
74 if (extract<X>(o).check()) { \
75 return object(to3D(extract<X>(o)())); \
78 template <
typename PtT>
81 return boost::geometry::distance(
p, utils::transform(range, [](
auto& v) {
return utils::toHybrid(v); }));
83 if (extract<ConstLineStrings2d>(lss).check()) {
84 return distance(
p, extract<ConstLineStrings2d>(lss)());
86 return distance(
p, extract<LineStrings2d>(lss)());
128 def(
"distance", lg::distance<BasicPoint2d, BasicPoint2d>);
129 def(
"distance", lg::distance<ConstPoint2d, ConstPoint2d>);
130 def(
"distance", lg::distance<ConstPoint2d, BasicPoint2d>);
131 def(
"distance", lg::distance<BasicPoint2d, ConstPoint2d>);
134 def(
"distance", lg::distance<ConstPoint2d, HybridLs2d>);
135 def(
"distance", lg::distance<HybridLs2d, ConstPoint2d>);
136 def(
"distance", lg::distance<ConstPoint2d, CompoundLineString2d>);
137 def(
"distance", lg::distance<CompoundLineString2d, ConstPoint2d>);
138 def(
"distance", lg::distance<ConstPoint2d, ConstLineString2d>);
139 def(
"distance", lg::distance<ConstLineString2d, ConstPoint2d>);
140 def(
"distance", lg::distance<ConstPoint2d, CompoundLineString2d>);
141 def(
"distance", lg::distance<CompoundLineString2d, ConstPoint2d>);
142 def(
"distance", lg::distance<BasicPoint2d, ConstLineString2d>);
143 def(
"distance", lg::distance<ConstLineString2d, BasicPoint2d>);
144 def(
"distance", lg::distance<BasicPoint2d, CompoundLineString2d>);
145 def(
"distance", lg::distance<CompoundLineString2d, BasicPoint2d>);
150 def(
"distance", lg::distance<ConstHybridLineString2d, ConstHybridLineString2d>);
162 def(
"distance", lg::distance<ConstHybridPolygon2d, BasicPoint2d>);
172 def(
"distance", lg::distance<ConstHybridPolygon2d, ConstHybridLineString2d>);
175 def(
"distance", lg::distance<ConstHybridLineString2d, ConstHybridPolygon2d>);
182 def(
"distance", lg::distance<ConstHybridPolygon2d, ConstHybridPolygon2d>);
208 def(
"distance", lg::distance<ConstPoint3d, ConstPoint3d>);
209 def(
"distance", lg::distance<ConstPoint3d, BasicPoint3d>);
210 def(
"distance", lg::distance<BasicPoint3d, ConstPoint3d>);
211 def(
"distance", lg::distance<BasicPoint3d, BasicPoint3d>);
214 def(
"distance", lg::distance<ConstPoint3d, HybridLs3d>);
215 def(
"distance", lg::distance<HybridLs3d, ConstPoint3d>);
216 def(
"distance", lg::distance<ConstPoint3d, CompoundLineString3d>);
217 def(
"distance", lg::distance<CompoundLineString3d, ConstPoint3d>);
218 def(
"distance", lg::distance<ConstPoint3d, ConstLineString3d>);
219 def(
"distance", lg::distance<ConstLineString3d, ConstPoint3d>);
222 def(
"distanceToLines", distancePointToLss<ConstPoint2d>);
223 def(
"distanceToLines", distancePointToLss<BasicPoint2d>);
229 "distance", +[](
const HybridLs3d& ls1,
const HybridLs3d& ls2) {
return lg::distance3d(ls1, ls2); });
241 def(
"distance", lg::distance3d<ConstLanelet, BasicPoint3d>);
242 def(
"distance", lg::distance3d<BasicPoint3d, ConstLanelet>);
251 def(
"equals", boost::geometry::equals<BasicPoint2d, BasicPoint2d>);
252 def(
"equals", boost::geometry::equals<ConstPoint2d, ConstPoint2d>);
253 def(
"equals", boost::geometry::equals<ConstPoint2d, BasicPoint2d>);
254 def(
"equals", boost::geometry::equals<BasicPoint2d, ConstPoint2d>);
257 def(
"equals", boost::geometry::equals<BasicPoint3d, BasicPoint3d>);
258 def(
"equals", boost::geometry::equals<ConstPoint3d, ConstPoint3d>);
259 def(
"equals", boost::geometry::equals<ConstPoint3d, BasicPoint3d>);
260 def(
"equals", boost::geometry::equals<BasicPoint3d, ConstPoint3d>);
262 def(
"boundingBox2d", boundingBox2dFor<ConstPoint2d>,
"Get the surrounding axis-aligned bounding box in 2d");
263 def(
"boundingBox2d", boundingBox2dFor<ConstLineString2d>);
264 def(
"boundingBox2d", boundingBox2dFor<ConstHybridLineString2d>);
265 def(
"boundingBox2d", boundingBox2dFor<ConstPolygon2d>);
266 def(
"boundingBox2d", boundingBox2dFor<ConstHybridPolygon2d>);
267 def(
"boundingBox2d", boundingBox2dFor<ConstLanelet>);
268 def(
"boundingBox2d", boundingBox2dFor<ConstArea>);
269 def(
"boundingBox2d", boundingBox2dFor<RegulatoryElementPtr>);
270 def(
"boundingBox2d", boundingBox2dFor<RegulatoryElementConstPtr>);
271 def(
"boundingBox2d", boundingBox2dFor<CompoundLineString2d>);
273 def(
"boundingBox3d", boundingBox3dFor<ConstPoint3d>,
"Get the surrounding axis-aligned bounding box in 3d");
274 def(
"boundingBox3d", boundingBox3dFor<ConstLineString3d>);
275 def(
"boundingBox3d", boundingBox3dFor<ConstHybridLineString3d>);
276 def(
"boundingBox3d", boundingBox3dFor<ConstPolygon3d>);
277 def(
"boundingBox3d", boundingBox3dFor<ConstHybridPolygon3d>);
278 def(
"boundingBox3d", boundingBox3dFor<ConstLanelet>);
279 def(
"boundingBox3d", boundingBox3dFor<ConstArea>);
280 def(
"boundingBox3d", boundingBox3dFor<RegulatoryElementPtr>);
281 def(
"boundingBox3d", boundingBox3dFor<RegulatoryElementConstPtr>);
282 def(
"boundingBox3d", boundingBox3dFor<CompoundLineString3d>);
285 def(
"area", boost::geometry::area<BasicPolygon2d>);
286 def(
"area", boost::geometry::area<ConstHybridPolygon2d>);
288 def(
"curvature2d", lg::curvature2d<BasicPoint2d>);
289 def(
"curvature2d", lg::curvature2d<ConstPoint2d>);
291 def(
"signedCurvature2d", lg::signedCurvature2d<BasicPoint2d>);
292 def(
"signedCurvature2d", lg::signedCurvature2d<ConstPoint2d>);
294 class_<ArcCoordinates>(
"ArcCoordinates",
"Coordinates along an arc", no_init)
295 .def(
"__init__", make_constructor(
296 +[](
double length,
double distance) {
299 default_call_policies(),
300 (arg(
"length") = 0., arg(
"distance") = 0.)))
301 .def_readwrite(
"length", &ArcCoordinates::length,
"length along arc")
302 .def_readwrite(
"distance", &ArcCoordinates::distance,
"signed distance to arc (left is positive")
308 return "ArcCoordinates(" + std::to_string(ac.
length) +
", " + std::to_string(ac.
distance) +
")";
311 def(
"toArcCoordinates", lg::toArcCoordinates<ConstLineString2d>,
312 "Project a point into arc coordinates of the linestring");
313 def(
"toArcCoordinates", lg::toArcCoordinates<CompoundLineString2d>,
314 "Project a point into arc coordinates of the linestring");
316 def(
"fromArcCoordinates", lg::fromArcCoordinates<ConstLineString2d>,
317 "Create a point from arc coordinates of the linestring");
318 def(
"fromArcCoordinates", lg::fromArcCoordinates<CompoundLineString2d>,
319 "Create a point from arc coordinates of the linestring");
321 def(
"length", lg::length<ConstLineString2d>);
322 def(
"length", lg::length<ConstLineString3d>);
323 def(
"length", lg::length<CompoundLineString2d>);
324 def(
"length", lg::length<CompoundLineString3d>);
326 def(
"interpolatedPointAtDistance", lg::interpolatedPointAtDistance<BasicLineString2d>);
327 def(
"interpolatedPointAtDistance", lg::interpolatedPointAtDistance<BasicLineString3d>);
328 def(
"interpolatedPointAtDistance", lg::interpolatedPointAtDistance<ConstLineString2d>);
329 def(
"interpolatedPointAtDistance", lg::interpolatedPointAtDistance<ConstLineString3d>);
330 def(
"interpolatedPointAtDistance", lg::interpolatedPointAtDistance<CompoundLineString2d>);
331 def(
"interpolatedPointAtDistance", lg::interpolatedPointAtDistance<CompoundLineString3d>);
333 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString2d>);
334 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString3d>);
335 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString2d>);
336 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString3d>);
338 def(
"project", lg::project<ConstLineString2d>,
"Project a point onto the linestring");
339 def(
"project", lg::project<ConstLineString3d>,
"Project a point onto the linestring");
340 def(
"project", lg::project<CompoundLineString2d>,
"Project a point onto the linestring");
341 def(
"project", lg::project<CompoundLineString3d>,
"Project a point onto the linestring");
343 def(
"projectedPoint3d", lg::projectedPoint3d<ConstLineString3d>,
344 "Returns the respective projected points of the closest distance of two "
346 def(
"projectedPoint3d", lg::projectedPoint3d<ConstHybridLineString3d>,
347 "Returns the respective projected points of the closest distance of two "
349 def(
"projectedPoint3d", lg::projectedPoint3d<CompoundLineString3d>,
350 "Returns the respective projected points of the closest distance of two "
351 "compound linestrings");
355 return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
357 def(
"intersects2d", lg::intersects<ConstHybridLineString2d, ConstHybridLineString2d>);
360 return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
364 return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
366 def(
"intersects2d", lg::intersects<ConstHybridPolygon2d, ConstHybridPolygon2d>);
367 def(
"intersects2d", lg::intersects<BoundingBox3d, BoundingBox3d>);
368 def(
"intersects2d", lg::intersects2d<ConstLanelet, ConstLanelet>);
369 def(
"intersects2d", lg::intersects2d<ConstArea, ConstArea>);
371 def(
"intersects3d", lg::intersects3d<ConstLineString3d>);
372 def(
"intersects3d", lg::intersects<BoundingBox3d, BoundingBox3d>);
373 def(
"intersects3d", lg::intersects3d<ConstHybridLineString3d>);
374 def(
"intersects3d", lg::intersects3d<CompoundLineString3d>);
375 def(
"intersects3d", lg::intersects3d<ConstLanelet, ConstLanelet>,
376 "Approximates if two lanelets intersect (touch or area >0) in 3d",
377 (arg(
"lanelet1"), arg(
"lanelet2"), arg(
"heightTolerance") = 3.));
379 def(
"inside", lg::inside<ConstLanelet>,
"tests whether a point is within a lanelet");
380 def(
"length2d", lg::length2d<ConstLanelet>,
"calculate length of centerline");
381 def(
"approximatedLength2d", lg::approximatedLength2d<ConstLanelet>,
382 "approximates length by sampling points along left bound");
383 def(
"length3d", lg::length3d<ConstLanelet>,
"calculate length of centerline in 3d");
384 def(
"distanceToCenterline2d", lg::distanceToCenterline2d<ConstLanelet>);
385 def(
"distanceToCenterline3d", lg::distanceToCenterline3d<ConstLanelet>);
386 def(
"overlaps2d", lg::overlaps2d<ConstLanelet, ConstLanelet>,
"Returns true if shared area of two lanelets is >0");
387 def(
"overlaps3d", lg::overlaps3d<ConstLanelet, ConstLanelet>,
"Approximates if two lanelets overlap (area >0) in 3d",
388 (arg(
"lanelet1"), arg(
"lanelet2"), arg(
"heightTolerance") = 3.));
394 def(
"leftOf", lg::leftOf<ConstLanelet, ConstLanelet>,
"Returns if first lanelet is directly left of second");
395 def(
"rightOf", lg::rightOf<ConstLanelet, ConstLanelet>,
"Returns if first lanelet is directly right of second");
396 def(
"follows", lg::follows<ConstLanelet, ConstLanelet>,
"Returns if first lanelet precedes the second");
398 wrapFindNearest<Point3d>();
399 wrapFindNearest<LineString3d>();
400 wrapFindNearest<Polygon3d>();
401 wrapFindNearest<Lanelet>();
402 wrapFindNearest<Area>();
403 wrapFindNearest<RegulatoryElementPtr>();
406 wrapFindWithin2d<Point3d, Point2d>();
407 wrapFindWithin2d<Point3d, BasicPoint2d>();
408 wrapFindWithin2d<Point3d, BoundingBox2d>();
409 wrapFindWithin2d<Point3d, Polygon2d>();
410 wrapFindWithin2d<Point3d, BasicPolygon2d>();
411 wrapFindWithin2d<Point3d, LineString2d>();
412 wrapFindWithin2d<Point3d, BasicLineString2d>();
413 wrapFindWithin2d<Point3d, CompoundLineString2d>();
414 wrapFindWithin2d<Point3d, Lanelet>();
415 wrapFindWithin2d<Point3d, Area>();
416 wrapFindWithin3d<Point3d, Point3d>();
417 wrapFindWithin3d<Point3d, BasicPoint3d>();
418 wrapFindWithin3d<Point3d, BoundingBox3d>();
419 wrapFindWithin3d<Point3d, Polygon3d>();
420 wrapFindWithin3d<Point3d, BasicPolygon3d>();
421 wrapFindWithin3d<Point3d, LineString3d>();
422 wrapFindWithin3d<Point3d, BasicLineString3d>();
423 wrapFindWithin3d<Point3d, CompoundLineString3d>();
424 wrapFindWithin3d<Point3d, Lanelet>();
425 wrapFindWithin3d<Point3d, Area>();
428 wrapFindWithin2d<LineString3d, Point2d>();
429 wrapFindWithin2d<LineString3d, BasicPoint2d>();
430 wrapFindWithin2d<LineString3d, BoundingBox2d>();
431 wrapFindWithin2d<LineString3d, Polygon2d>();
432 wrapFindWithin2d<LineString3d, BasicPolygon2d>();
433 wrapFindWithin2d<LineString3d, LineString2d>();
434 wrapFindWithin2d<LineString3d, Lanelet>();
435 wrapFindWithin2d<LineString3d, Area>();
436 wrapFindWithin2d<LineString3d, BasicLineString2d>();
437 wrapFindWithin2d<LineString3d, CompoundLineString2d>();
438 wrapFindWithin3d<LineString3d, Point3d>();
439 wrapFindWithin3d<LineString3d, BasicPoint3d>();
442 wrapFindWithin2d<Polygon3d, Point2d>();
443 wrapFindWithin2d<Polygon3d, BasicPoint2d>();
444 wrapFindWithin2d<Polygon3d, BoundingBox2d>();
445 wrapFindWithin2d<Polygon3d, Polygon2d>();
446 wrapFindWithin2d<Polygon3d, BasicPolygon2d>();
447 wrapFindWithin2d<Polygon3d, LineString2d>();
448 wrapFindWithin2d<Polygon3d, BasicLineString2d>();
449 wrapFindWithin2d<Polygon3d, CompoundLineString2d>();
450 wrapFindWithin2d<Polygon3d, Lanelet>();
451 wrapFindWithin2d<Polygon3d, Area>();
452 wrapFindWithin3d<Polygon3d, Point3d>();
453 wrapFindWithin3d<Polygon3d, BasicPoint3d>();
456 wrapFindWithin2d<Lanelet, Point2d>();
457 wrapFindWithin2d<Lanelet, BasicPoint2d>();
458 wrapFindWithin2d<Lanelet, BoundingBox2d>();
459 wrapFindWithin2d<Lanelet, Polygon2d>();
460 wrapFindWithin2d<Lanelet, BasicPolygon2d>();
461 wrapFindWithin2d<Lanelet, LineString2d>();
462 wrapFindWithin2d<Lanelet, BasicLineString2d>();
463 wrapFindWithin2d<Lanelet, CompoundLineString2d>();
464 wrapFindWithin2d<Lanelet, Lanelet>();
465 wrapFindWithin2d<Lanelet, Area>();
466 wrapFindWithin3d<Lanelet, Point3d>();
467 wrapFindWithin3d<Lanelet, BasicPoint3d>();
470 wrapFindWithin2d<Area, Point2d>();
471 wrapFindWithin2d<Area, BasicPoint2d>();
472 wrapFindWithin2d<Area, BoundingBox2d>();
473 wrapFindWithin2d<Area, Polygon2d>();
474 wrapFindWithin2d<Area, BasicPolygon2d>();
475 wrapFindWithin2d<Area, LineString2d>();
476 wrapFindWithin2d<Area, BasicLineString2d>();
477 wrapFindWithin2d<Area, CompoundLineString2d>();
478 wrapFindWithin2d<Area, Lanelet>();
479 wrapFindWithin2d<Area, Area>();
480 wrapFindWithin3d<Area, Point3d>();
481 wrapFindWithin3d<Area, BasicPoint3d>();
487 boost::geometry::intersection(ls1, ls2, pts);