geometry.cpp
Go to the documentation of this file.
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>
8 
9 #include <boost/geometry/algorithms/intersection.hpp>
10 #include <boost/geometry/geometries/register/multi_linestring.hpp>
11 
14 
15 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::LineStrings2d)
16 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstLineStrings2d)
17 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstHybridLineStrings2d)
18 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::CompoundLineStrings2d)
19 
20 using namespace boost::python;
21 using namespace lanelet;
22 
25 
26 template <typename PrimT>
28  using ResultT = std::vector<std::pair<double, PrimT>>;
29  using Sig = ResultT (*)(PrimitiveLayer<PrimT>&, const BasicPoint2d&, unsigned);
30  auto func = static_cast<Sig>(lanelet::geometry::findNearest);
33  return def("findNearest", func);
34 }
35 template <typename PrimT, typename GeometryT>
37  using ResultT = std::vector<std::pair<double, PrimT>>;
38  using Sig = ResultT (*)(PrimitiveLayer<PrimT>&, const GeometryT&, double);
39  auto func = static_cast<Sig>(lanelet::geometry::findWithin2d);
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");
42 }
43 template <typename PrimT, typename GeometryT>
45  using ResultT = std::vector<std::pair<double, PrimT>>;
46  using Sig = ResultT (*)(PrimitiveLayer<PrimT>&, const GeometryT&, double);
47  auto func = static_cast<Sig>(lanelet::geometry::findWithin3d);
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");
50 }
51 
52 std::vector<BasicPoint2d> toBasicVector(const BasicPoints2d& pts) {
53  return utils::transform(pts, [](auto& p) { return BasicPoint2d(p.x(), p.y()); });
54 }
55 
56 template <typename T>
59 }
60 
61 template <typename T>
64 }
65 
66 // NOLINTNEXTLINE(cppcoreguidelines-macro-usage)
67 #define TO2D_AS(X) \
68  if (extract<X>(o).check()) { \
69  return object(to2D(extract<X>(o)())); \
70  }
71 
72 // NOLINTNEXTLINE(cppcoreguidelines-macro-usage)
73 #define TO3D_AS(X) \
74  if (extract<X>(o).check()) { \
75  return object(to3D(extract<X>(o)())); \
76  }
77 
78 template <typename PtT>
79 double distancePointToLss(const PtT& p, const object& lss) {
80  auto distance = [](PtT p, auto range) {
81  return boost::geometry::distance(p, utils::transform(range, [](auto& v) { return utils::toHybrid(v); }));
82  };
83  if (extract<ConstLineStrings2d>(lss).check()) {
84  return distance(p, extract<ConstLineStrings2d>(lss)());
85  }
86  return distance(p, extract<LineStrings2d>(lss)());
87 }
88 
89 object to2D(object o) {
90  using utils::to2D;
101  return o;
102 }
103 
104 object to3D(object o) {
105  using utils::to3D;
116  return o;
117 }
118 #undef TO2D_AS
119 #undef TO3D_AS
120 
121 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
122  namespace lg = lanelet::geometry;
123 
124  def("to2D", to2D);
125  def("to3D", to3D);
126 
127  // p2p
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>);
132 
133  // p2l
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>);
146 
147  // l2l
148  def(
149  "distance", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
150  def("distance", lg::distance<ConstHybridLineString2d, ConstHybridLineString2d>);
151  def(
152  "distance",
153  +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
154  def(
155  "distance",
156  +[](const ConstLineString2d& ls1, const CompoundLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
157  def(
158  "distance",
159  +[](const CompoundLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
160 
161  // poly2p
162  def("distance", lg::distance<ConstHybridPolygon2d, BasicPoint2d>);
163  def(
164  "distance", +[](const ConstPolygon2d& p1, const BasicPoint2d& p2) { return lg::distance2d(p1, p2); });
165  def(
166  "distance",
167  +[](const ConstPolygon2d& p1, const ConstPoint2d& p2) { return lg::distance2d(p1, p2.basicPoint()); });
168 
169  // poly2ls
170  def(
171  "distance", +[](const ConstPolygon2d& p1, const ConstLineString2d& p2) { return lg::distance2d(p1, p2); });
172  def("distance", lg::distance<ConstHybridPolygon2d, ConstHybridLineString2d>);
173  def(
174  "distance", +[](const ConstLineString2d& p2, const ConstPolygon2d& p1) { return lg::distance2d(p1, p2); });
175  def("distance", lg::distance<ConstHybridLineString2d, ConstHybridPolygon2d>);
176  def(
177  "distance", +[](const ConstPolygon2d& p1, const CompoundLineString2d& p2) { return lg::distance2d(p1, p2); });
178  def(
179  "distance", +[](const CompoundLineString2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
180 
181  // poly2poly
182  def("distance", lg::distance<ConstHybridPolygon2d, ConstHybridPolygon2d>);
183  def(
184  "distance", +[](const ConstPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
185  def(
186  "distance", +[](const ConstHybridPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
187  def(
188  "distance", +[](const CompoundPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
189  def(
190  "distance", +[](const ConstPolygon2d& p1, const ConstHybridPolygon2d& p2) { return lg::distance2d(p1, p2); });
191 
192  // p2llt
193  def(
194  "distance", +[](const ConstLanelet& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); });
195  def(
196  "distance", +[](const ConstLanelet& llt1, const ConstLanelet& llt2) { return lg::distance2d(llt1, llt2); });
197  def(
198  "distance", +[](const BasicPoint2d& p, const ConstLanelet& llt) { return lg::distance2d(llt, p); });
199 
200  // p2area
201  def(
202  "distance", +[](const ConstArea& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); });
203  def(
204  "distance", +[](const BasicPoint2d& p, const ConstArea& llt) { return lg::distance2d(llt, p); });
205 
206  // 3d
207  // p2p
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>);
212 
213  // p2l
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>);
220 
221  // p2lines
222  def("distanceToLines", distancePointToLss<ConstPoint2d>);
223  def("distanceToLines", distancePointToLss<BasicPoint2d>);
224 
225  // l2l
226  def(
227  "distance", +[](const ConstLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
228  def(
229  "distance", +[](const HybridLs3d& ls1, const HybridLs3d& ls2) { return lg::distance3d(ls1, ls2); });
230  def(
231  "distance",
232  +[](const CompoundLineString3d& ls1, const CompoundLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
233  def(
234  "distance",
235  +[](const ConstLineString3d& ls1, const CompoundLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
236  def(
237  "distance",
238  +[](const CompoundLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
239 
240  // p2llt
241  def("distance", lg::distance3d<ConstLanelet, BasicPoint3d>);
242  def("distance", lg::distance3d<BasicPoint3d, ConstLanelet>);
243 
244  // p2area
245  def(
246  "distance", +[](const ConstArea& llt, const BasicPoint3d& p) { return lg::distance3d(llt, p); });
247  def(
248  "distance", +[](const BasicPoint3d& p, const ConstArea& llt) { return lg::distance3d(llt, p); });
249 
250  // equals 2d
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>);
255 
256  // equals 3d
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>);
261 
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>);
272 
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>);
283 
284  // area
285  def("area", boost::geometry::area<BasicPolygon2d>);
286  def("area", boost::geometry::area<ConstHybridPolygon2d>);
287 
288  def("curvature2d", lg::curvature2d<BasicPoint2d>);
289  def("curvature2d", lg::curvature2d<ConstPoint2d>);
290 
291  def("signedCurvature2d", lg::signedCurvature2d<BasicPoint2d>);
292  def("signedCurvature2d", lg::signedCurvature2d<ConstPoint2d>);
293 
294  class_<ArcCoordinates>("ArcCoordinates", "Coordinates along an arc", no_init)
295  .def("__init__", make_constructor(
296  +[](double length, double distance) {
297  return std::make_shared<ArcCoordinates>(ArcCoordinates{length, distance});
298  },
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")
303  .def(
304  "__eq__", +[](const ArcCoordinates& ac1,
305  const ArcCoordinates& ac2) { return ac1.length == ac2.length && ac1.distance == ac2.distance; })
306  .def(
307  "__repr__", +[](const ArcCoordinates& ac) {
308  return "ArcCoordinates(" + std::to_string(ac.length) + ", " + std::to_string(ac.distance) + ")";
309  });
310 
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");
315 
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");
320 
321  def("length", lg::length<ConstLineString2d>);
322  def("length", lg::length<ConstLineString3d>);
323  def("length", lg::length<CompoundLineString2d>);
324  def("length", lg::length<CompoundLineString3d>);
325 
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>);
332 
333  def("nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString2d>);
334  def("nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString3d>);
335  def("nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString2d>);
336  def("nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString3d>);
337 
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");
342 
343  def("projectedPoint3d", lg::projectedPoint3d<ConstLineString3d>,
344  "Returns the respective projected points of the closest distance of two "
345  "linestrings");
346  def("projectedPoint3d", lg::projectedPoint3d<ConstHybridLineString3d>,
347  "Returns the respective projected points of the closest distance of two "
348  "linestrings");
349  def("projectedPoint3d", lg::projectedPoint3d<CompoundLineString3d>,
350  "Returns the respective projected points of the closest distance of two "
351  "compound linestrings");
352 
353  def(
354  "intersects2d", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) {
355  return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
356  });
357  def("intersects2d", lg::intersects<ConstHybridLineString2d, ConstHybridLineString2d>);
358  def(
359  "intersects2d", +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) {
360  return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
361  });
362  def(
363  "intersects2d", +[](const ConstPolygon2d& ls1, const ConstPolygon2d& ls2) {
364  return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
365  });
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>);
370 
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.));
378 
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.));
389  def(
390  "intersectCenterlines2d", +[](const ConstLanelet& ll1, const ConstLanelet& ll2) {
391  return toBasicVector(lg::intersectCenterlines2d(ll1, ll2));
392  });
393 
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");
397 
398  wrapFindNearest<Point3d>();
399  wrapFindNearest<LineString3d>();
400  wrapFindNearest<Polygon3d>();
401  wrapFindNearest<Lanelet>();
402  wrapFindNearest<Area>();
403  wrapFindNearest<RegulatoryElementPtr>();
404 
405  // find within, point layer
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>();
426 
427  // linestring layer
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>();
440 
441  // polygon layer
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>();
454 
455  // lanelet layer
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>();
468 
469  // area layer
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>();
482 
483  // boost::geometry functions for convenience
484  def(
485  "intersection", +[](const BasicLineString2d& ls1, const BasicLineString2d& ls2) {
486  BasicPoints2d pts;
487  boost::geometry::intersection(ls1, ls2, pts);
488  return toBasicVector(pts);
489  });
490 
491  def(
492  "intersection", +[](const CompoundLineString2d& ls1, const ConstLineString2d& ls2) {
493  BasicPoints2d pts;
494  boost::geometry::intersection(ls1.basicLineString(), ls2.basicLineString(), pts);
495  return toBasicVector(pts);
496  });
497 
498  def(
499  "intersection", +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) {
500  BasicPoints2d pts;
501  boost::geometry::intersection(ls1.basicLineString(), ls2.basicLineString(), pts);
502  return toBasicVector(pts);
503  });
504 
505  def(
506  "intersection", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) {
507  BasicPoints2d pts;
508  boost::geometry::intersection(ls1.basicLineString(), ls2.basicLineString(), pts);
509  return toBasicVector(pts);
510  });
511 }
lanelet::ArcCoordinates::length
double length
toBasicVector
std::vector< BasicPoint2d > toBasicVector(const BasicPoints2d &pts)
Definition: geometry.cpp:52
lanelet::geometry::boundingBox3d
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
ConstLineStringImpl< Point2d >::basicLineString
BasicLineString basicLineString() const noexcept
TO3D_AS
#define TO3D_AS(X)
Definition: geometry.cpp:73
CompoundPolygon.h
lanelet::LineStrings2d
std::vector< LineString2d > LineStrings2d
lanelet::CompoundPolygon3d
LaneletMap.h
lanelet
to3D
object to3D(object o)
Definition: geometry.cpp:104
BasicPoint3d
Eigen::Vector3d BasicPoint3d
lanelet::ConstArea
p2
BasicPoint p2
p
BasicPoint p
to2D
object to2D(object o)
Definition: geometry.cpp:89
lanelet::Point2d
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: geometry.cpp:121
lanelet::ConstPolygon3d
lanelet::geometry::findWithin3d
auto findWithin3d(LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>>
distancePointToLss
double distancePointToLss(const PtT &p, const object &lss)
Definition: geometry.cpp:79
lanelet::ArcCoordinates::distance
double distance
lanelet::ArcCoordinates
lanelet::ConstHybridLineString2d
lanelet::CompoundLineString3d
lanelet::ConstLineString2d
lanelet::Polygon2d
lanelet::BoundingBox2d
lanelet::LineString2d
converter.h
lanelet::ConstPoint3d
wrapFindWithin2d
auto wrapFindWithin2d()
Definition: geometry.cpp:36
lanelet::BoundingBox3d
Eigen::AlignedBox3d BoundingBox3d
lanelet::PrimitiveLayer
CompoundLineStringImpl< ConstPoint2d >::basicLineString
BasicLineString basicLineString() const
BasicLineString2d
BasicPoints2d BasicLineString2d
TO2D_AS
#define TO2D_AS(X)
Definition: geometry.cpp:67
lanelet::CompoundPolygon2d
p1
BasicPoint p1
boundingBox3dFor
lanelet::BoundingBox3d boundingBox3dFor(const T &t)
Definition: geometry.cpp:62
lanelet::ConstLineStrings2d
std::vector< ConstLineString2d > ConstLineStrings2d
BasicPoint2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
lanelet::geometry::findWithin2d
auto findWithin2d(LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>>
lanelet::Point3d
lanelet::geometry::findNearest
std::vector< std::pair< double, traits::ConstPrimitiveType< PrimT > > > findNearest(const PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count)
lanelet::ConstPolygon2d
wrapFindNearest
auto wrapFindNearest()
Definition: geometry.cpp:27
lanelet::ConstHybridPolygon2d
lanelet::geometry::boundingBox2d
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
converters::VectorToListConverter
py::to_python_converter< T, VectorToList< T > > VectorToListConverter
Definition: converter.h:219
boundingBox2dFor
lanelet::BoundingBox2d boundingBox2dFor(const T &t)
Definition: geometry.cpp:57
lanelet::CompoundLineString2d
lanelet::ConstLineString3d
lanelet::Polygon3d
lanelet::ConstLanelet
distance
Optional< double > distance
lanelet::ConstHybridLineString3d
lanelet::geometry
converters::PyPair
Definition: converter.h:213
lanelet::LineString3d
wrapFindWithin3d
auto wrapFindWithin3d()
Definition: geometry.cpp:44
lanelet::ConstHybridLineStrings2d
std::vector< ConstHybridLineString2d > ConstHybridLineStrings2d
lanelet::ConstPoint2d
BasicPoints2d
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > BasicPoints2d
lanelet::CompoundLineStrings2d
std::vector< CompoundLineString2d > CompoundLineStrings2d


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:14