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 
13 
14 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::LineStrings2d)
15 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstLineStrings2d)
16 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::ConstHybridLineStrings2d)
17 BOOST_GEOMETRY_REGISTER_MULTI_LINESTRING(lanelet::CompoundLineStrings2d)
18 
19 using namespace boost::python;
20 using namespace lanelet;
21 
24 
25 template <typename PrimT>
27  using ResultT = std::vector<std::pair<double, PrimT>>;
28  using Sig = ResultT (*)(PrimitiveLayer<PrimT>&, const BasicPoint2d&, unsigned);
29  auto func = static_cast<Sig>(lanelet::geometry::findNearest);
32  return def("findNearest", func);
33 }
34 template <typename PrimT, typename GeometryT>
36  using ResultT = std::vector<std::pair<double, PrimT>>;
37  using Sig = ResultT (*)(PrimitiveLayer<PrimT>&, const GeometryT&, double);
38  auto func = static_cast<Sig>(lanelet::geometry::findWithin2d);
39  return def("findWithin2d", func, (arg("layer"), arg("geometry"), arg("maxDist") = 0),
40  "returns all elements that are closer than maxDist to a geometry in 2d");
41 }
42 template <typename PrimT, typename GeometryT>
44  using ResultT = std::vector<std::pair<double, PrimT>>;
45  using Sig = ResultT (*)(PrimitiveLayer<PrimT>&, const GeometryT&, double);
46  auto func = static_cast<Sig>(lanelet::geometry::findWithin3d);
47  return def("findWithin3d", func, (arg("layer"), arg("geometry"), arg("maxDist") = 0),
48  "returns all elements that are closer than maxDist to a geometry in 3d");
49 }
50 
51 std::vector<BasicPoint2d> toBasicVector(const BasicPoints2d& pts) {
52  return utils::transform(pts, [](auto& p) { return BasicPoint2d(p.x(), p.y()); });
53 }
54 
55 template <typename T>
58 }
59 
60 template <typename T>
63 }
64 
65 // NOLINTNEXTLINE(cppcoreguidelines-macro-usage)
66 #define TO2D_AS(X) \
67  if (extract<X>(o).check()) { \
68  return object(to2D(extract<X>(o)())); \
69  }
70 
71 // NOLINTNEXTLINE(cppcoreguidelines-macro-usage)
72 #define TO3D_AS(X) \
73  if (extract<X>(o).check()) { \
74  return object(to3D(extract<X>(o)())); \
75  }
76 
77 template <typename PtT>
78 double distancePointToLss(const PtT& p, const object& lss) {
79  auto distance = [](PtT p, auto range) {
80  return boost::geometry::distance(p, utils::transform(range, [](auto& v) { return utils::toHybrid(v); }));
81  };
82  if (extract<ConstLineStrings2d>(lss).check()) {
83  return distance(p, extract<ConstLineStrings2d>(lss)());
84  }
85  return distance(p, extract<LineStrings2d>(lss)());
86 }
87 
88 object to2D(object o) {
89  using utils::to2D;
99  return o;
100 }
101 
102 object to3D(object o) {
103  using utils::to3D;
113  return o;
114 }
115 #undef TO2D_AS
116 #undef TO3D_AS
117 
118 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
119  namespace lg = lanelet::geometry;
120 
121  def("to2D", to2D);
122  def("to3D", to3D);
123 
124  // p2p
125  def("distance", lg::distance<BasicPoint2d, BasicPoint2d>);
126  def("distance", lg::distance<ConstPoint2d, ConstPoint2d>);
127  def("distance", lg::distance<ConstPoint2d, BasicPoint2d>);
128  def("distance", lg::distance<BasicPoint2d, ConstPoint2d>);
129 
130  // p2l
131  def("distance", lg::distance<ConstPoint2d, HybridLs2d>);
132  def("distance", lg::distance<HybridLs2d, ConstPoint2d>);
133  def("distance", lg::distance<ConstPoint2d, CompoundLineString2d>);
134  def("distance", lg::distance<CompoundLineString2d, ConstPoint2d>);
135  def("distance", lg::distance<ConstPoint2d, ConstLineString2d>);
136  def("distance", lg::distance<ConstLineString2d, ConstPoint2d>);
137  def("distance", lg::distance<ConstPoint2d, CompoundLineString2d>);
138  def("distance", lg::distance<CompoundLineString2d, ConstPoint2d>);
139  def("distance", lg::distance<BasicPoint2d, ConstLineString2d>);
140  def("distance", lg::distance<ConstLineString2d, BasicPoint2d>);
141  def("distance", lg::distance<BasicPoint2d, CompoundLineString2d>);
142  def("distance", lg::distance<CompoundLineString2d, BasicPoint2d>);
143 
144  // l2l
145  def(
146  "distance", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
147  def("distance", lg::distance<ConstHybridLineString2d, ConstHybridLineString2d>);
148  def(
149  "distance",
150  +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
151  def(
152  "distance",
153  +[](const ConstLineString2d& ls1, const CompoundLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
154  def(
155  "distance",
156  +[](const CompoundLineString2d& ls1, const ConstLineString2d& ls2) { return lg::distance2d(ls1, ls2); });
157 
158  // poly2p
159  def("distance", lg::distance<ConstHybridPolygon2d, BasicPoint2d>);
160  def(
161  "distance", +[](const ConstPolygon2d& p1, const BasicPoint2d& p2) { return lg::distance2d(p1, p2); });
162  def(
163  "distance",
164  +[](const ConstPolygon2d& p1, const ConstPoint2d& p2) { return lg::distance2d(p1, p2.basicPoint()); });
165 
166  // poly2ls
167  def(
168  "distance", +[](const ConstPolygon2d& p1, const ConstLineString2d& p2) { return lg::distance2d(p1, p2); });
169  def("distance", lg::distance<ConstHybridPolygon2d, ConstHybridLineString2d>);
170  def(
171  "distance", +[](const ConstLineString2d& p2, const ConstPolygon2d& p1) { return lg::distance2d(p1, p2); });
172  def("distance", lg::distance<ConstHybridLineString2d, ConstHybridPolygon2d>);
173  def(
174  "distance", +[](const ConstPolygon2d& p1, const CompoundLineString2d& p2) { return lg::distance2d(p1, p2); });
175  def(
176  "distance", +[](const CompoundLineString2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
177 
178  // poly2poly
179  def("distance", lg::distance<ConstHybridPolygon2d, ConstHybridPolygon2d>);
180  def(
181  "distance", +[](const ConstPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
182  def(
183  "distance", +[](const ConstHybridPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
184  def(
185  "distance", +[](const CompoundPolygon2d& p1, const ConstPolygon2d& p2) { return lg::distance2d(p1, p2); });
186  def(
187  "distance", +[](const ConstPolygon2d& p1, const ConstHybridPolygon2d& p2) { return lg::distance2d(p1, p2); });
188 
189  // p2llt
190  def(
191  "distance", +[](const ConstLanelet& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); });
192  def(
193  "distance", +[](const ConstLanelet& llt1, const ConstLanelet& llt2) { return lg::distance2d(llt1, llt2); });
194  def(
195  "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); });
198 
199  // p2area
200  def(
201  "distance", +[](const ConstArea& llt, const BasicPoint2d& p) { return lg::distance2d(llt, p); });
202  def(
203  "distance", +[](const BasicPoint2d& p, const ConstArea& llt) { return lg::distance2d(llt, p); });
204 
205  // 3d
206  // p2p
207  def("distance", lg::distance<ConstPoint3d, ConstPoint3d>);
208  def("distance", lg::distance<ConstPoint3d, BasicPoint3d>);
209  def("distance", lg::distance<BasicPoint3d, ConstPoint3d>);
210  def("distance", lg::distance<BasicPoint3d, BasicPoint3d>);
211 
212  // p2l
213  def("distance", lg::distance<ConstPoint3d, HybridLs3d>);
214  def("distance", lg::distance<HybridLs3d, ConstPoint3d>);
215  def("distance", lg::distance<ConstPoint3d, CompoundLineString3d>);
216  def("distance", lg::distance<CompoundLineString3d, ConstPoint3d>);
217  def("distance", lg::distance<ConstPoint3d, ConstLineString3d>);
218  def("distance", lg::distance<ConstLineString3d, ConstPoint3d>);
219  def("distance", lg::distance<ConstPoint3d, CompoundLineString3d>);
220  def("distance", lg::distance<CompoundLineString3d, ConstPoint3d>);
221 
222  // p2lines
223  def("distanceToLines", distancePointToLss<ConstPoint2d>);
224  def("distanceToLines", distancePointToLss<BasicPoint2d>);
225  def("distanceToLines", distancePointToLss<ConstPoint2d>);
226  def("distanceToLines", distancePointToLss<BasicPoint2d>);
227 
228  // l2l
229  def(
230  "distance", +[](const ConstLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
231  def(
232  "distance", +[](const HybridLs3d& ls1, const HybridLs3d& ls2) { return lg::distance3d(ls1, ls2); });
233  def(
234  "distance",
235  +[](const CompoundLineString3d& ls1, const CompoundLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
236  def(
237  "distance",
238  +[](const ConstLineString3d& ls1, const CompoundLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
239  def(
240  "distance",
241  +[](const CompoundLineString3d& ls1, const ConstLineString3d& ls2) { return lg::distance3d(ls1, ls2); });
242 
243  // p2llt
244  def("distance", lg::distance3d<ConstLanelet, BasicPoint3d>);
245  def("distance", lg::distance3d<BasicPoint3d, ConstLanelet>);
246 
247  // p2area
248  def(
249  "distance", +[](const ConstArea& llt, const BasicPoint3d& p) { return lg::distance3d(llt, p); });
250  def(
251  "distance", +[](const BasicPoint3d& p, const ConstArea& llt) { return lg::distance3d(llt, p); });
252 
253  // equals 2d
254  def("equals", boost::geometry::equals<BasicPoint2d, BasicPoint2d>);
255  def("equals", boost::geometry::equals<ConstPoint2d, ConstPoint2d>);
256  def("equals", boost::geometry::equals<ConstPoint2d, BasicPoint2d>);
257  def("equals", boost::geometry::equals<BasicPoint2d, ConstPoint2d>);
258 
259  // equals 3d
260  def("equals", boost::geometry::equals<BasicPoint3d, BasicPoint3d>);
261  def("equals", boost::geometry::equals<ConstPoint3d, ConstPoint3d>);
262  def("equals", boost::geometry::equals<ConstPoint3d, BasicPoint3d>);
263  def("equals", boost::geometry::equals<BasicPoint3d, ConstPoint3d>);
264 
265  def("boundingBox2d", boundingBox2dFor<ConstPoint2d>, "Get the surrounding axis-aligned bounding box in 2d");
266  def("boundingBox2d", boundingBox2dFor<ConstLineString2d>);
267  def("boundingBox2d", boundingBox2dFor<ConstHybridLineString2d>);
268  def("boundingBox2d", boundingBox2dFor<ConstPolygon2d>);
269  def("boundingBox2d", boundingBox2dFor<ConstHybridPolygon2d>);
270  def("boundingBox2d", boundingBox2dFor<ConstLanelet>);
271  def("boundingBox2d", boundingBox2dFor<ConstArea>);
272  def("boundingBox2d", boundingBox2dFor<RegulatoryElementPtr>);
273  def("boundingBox2d", boundingBox2dFor<RegulatoryElementConstPtr>);
274  def("boundingBox2d", boundingBox2dFor<CompoundLineString2d>);
275 
276  def("boundingBox3d", boundingBox3dFor<ConstPoint3d>, "Get the surrounding axis-aligned bounding box in 3d");
277  def("boundingBox3d", boundingBox3dFor<ConstLineString3d>);
278  def("boundingBox3d", boundingBox3dFor<ConstHybridLineString3d>);
279  def("boundingBox3d", boundingBox3dFor<ConstPolygon3d>);
280  def("boundingBox3d", boundingBox3dFor<ConstHybridPolygon3d>);
281  def("boundingBox3d", boundingBox3dFor<ConstLanelet>);
282  def("boundingBox3d", boundingBox3dFor<ConstArea>);
283  def("boundingBox3d", boundingBox3dFor<RegulatoryElementPtr>);
284  def("boundingBox3d", boundingBox3dFor<RegulatoryElementConstPtr>);
285  def("boundingBox3d", boundingBox3dFor<CompoundLineString3d>);
286 
287  // area
288  def("area", boost::geometry::area<BasicPolygon2d>);
289  def("area", boost::geometry::area<ConstHybridPolygon2d>);
290 
291  class_<ArcCoordinates>("ArcCoordinates", "Coordinates along an arc", init<>())
292  .def_readwrite("length", &ArcCoordinates::length, "length along arc")
293  .def_readwrite("distance", &ArcCoordinates::distance, "signed distance to arc (left is positive");
294 
295  def("toArcCoordinates", lg::toArcCoordinates<ConstLineString2d>,
296  "Project a point into arc coordinates of the linestring");
297  def("toArcCoordinates", lg::toArcCoordinates<CompoundLineString2d>,
298  "Project a point into arc coordinates of the linestring");
299 
300  def("fromArcCoordinates", lg::fromArcCoordinates<ConstLineString2d>,
301  "Create a point from arc coordinates of the linestring");
302  def("fromArcCoordinates", lg::fromArcCoordinates<CompoundLineString2d>,
303  "Create a point from arc coordinates of the linestring");
304 
305  def("length", lg::length<ConstLineString2d>);
306  def("length", lg::length<ConstLineString3d>);
307  def("length", lg::length<CompoundLineString2d>);
308  def("length", lg::length<CompoundLineString3d>);
309 
310  def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance<BasicLineString2d>);
311  def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance<BasicLineString3d>);
312  def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance<ConstLineString2d>);
313  def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance<ConstLineString3d>);
314  def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance<CompoundLineString2d>);
315  def("interpolatedPointAtDistance", lg::interpolatedPointAtDistance<CompoundLineString3d>);
316 
317  def("nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString2d>);
318  def("nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString3d>);
319  def("nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString2d>);
320  def("nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString3d>);
321 
322  def("project", lg::project<ConstLineString2d>, "Project a point onto the linestring");
323  def("project", lg::project<ConstLineString3d>, "Project a point onto the linestring");
324  def("project", lg::project<CompoundLineString2d>, "Project a point onto the linestring");
325  def("project", lg::project<CompoundLineString3d>, "Project a point onto the linestring");
326 
327  def("projectedPoint3d", lg::projectedPoint3d<ConstLineString3d>,
328  "Returns the respective projected points of the closest distance of two "
329  "linestrings");
330  def("projectedPoint3d", lg::projectedPoint3d<ConstHybridLineString3d>,
331  "Returns the respective projected points of the closest distance of two "
332  "linestrings");
333  def("projectedPoint3d", lg::projectedPoint3d<CompoundLineString3d>,
334  "Returns the respective projected points of the closest distance of two "
335  "compound linestrings");
336 
337  def(
338  "intersects2d", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) {
339  return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
340  });
341  def("intersects2d", lg::intersects<ConstHybridLineString2d, ConstHybridLineString2d>);
342  def(
343  "intersects2d", +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) {
344  return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
345  });
346  def(
347  "intersects2d", +[](const ConstPolygon2d& ls1, const ConstPolygon2d& ls2) {
348  return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
349  });
350  def("intersects2d", lg::intersects<ConstHybridPolygon2d, ConstHybridPolygon2d>);
351  def("intersects2d", lg::intersects<BoundingBox3d, BoundingBox3d>);
352  def("intersects2d", lg::intersects2d<ConstLanelet, ConstLanelet>);
353  def("intersects2d", lg::intersects2d<ConstArea, ConstArea>);
354 
355  def("intersects3d", lg::intersects3d<ConstLineString3d>);
356  def("intersects3d", lg::intersects<BoundingBox3d, BoundingBox3d>);
357  def("intersects3d", lg::intersects3d<ConstHybridLineString3d>);
358  def("intersects3d", lg::intersects3d<CompoundLineString3d>);
359  def("intersects3d", lg::intersects3d<ConstLanelet, ConstLanelet>,
360  "Approximates if two lanelets intersect (touch or area >0) in 3d",
361  (arg("lanelet1"), arg("lanelet2"), arg("heightTolerance") = 3.));
362 
363  def("inside", lg::inside<ConstLanelet>, "tests whether a point is within a lanelet");
364  def("length2d", lg::length2d<ConstLanelet>, "calculate length of centerline");
365  def("approximatedLength2d", lg::approximatedLength2d<ConstLanelet>,
366  "approximates length by sampling points along left bound");
367  def("length3d", lg::length3d<ConstLanelet>, "calculate length of centerline in 3d");
368  def("distanceToCenterline2d", lg::distanceToCenterline2d<ConstLanelet>);
369  def("distanceToCenterline3d", lg::distanceToCenterline3d<ConstLanelet>);
370  def("overlaps2d", lg::overlaps2d<ConstLanelet, ConstLanelet>, "Returns true if shared area of two lanelets is >0");
371  def("overlaps3d", lg::overlaps3d<ConstLanelet, ConstLanelet>, "Approximates if two lanelets overlap (area >0) in 3d",
372  (arg("lanelet1"), arg("lanelet2"), arg("heightTolerance") = 3.));
373  def(
374  "intersectCenterlines2d", +[](const ConstLanelet& ll1, const ConstLanelet& ll2) {
375  return toBasicVector(lg::intersectCenterlines2d(ll1, ll2));
376  });
377 
378  def("leftOf", lg::leftOf<ConstLanelet, ConstLanelet>, "Returns if first lanelet is directly left of second");
379  def("rightOf", lg::rightOf<ConstLanelet, ConstLanelet>, "Returns if first lanelet is directly right of second");
380  def("follows", lg::follows<ConstLanelet, ConstLanelet>, "Returns if first lanelet precedes the second");
381 
382  wrapFindNearest<Point3d>();
383  wrapFindNearest<LineString3d>();
384  wrapFindNearest<Polygon3d>();
385  wrapFindNearest<Lanelet>();
386  wrapFindNearest<Area>();
387  wrapFindNearest<RegulatoryElementPtr>();
388 
389  // find within, point layer
390  wrapFindWithin2d<Point3d, Point2d>();
391  wrapFindWithin2d<Point3d, BasicPoint2d>();
392  wrapFindWithin2d<Point3d, BoundingBox2d>();
393  wrapFindWithin2d<Point3d, Polygon2d>();
394  wrapFindWithin2d<Point3d, BasicPolygon2d>();
395  wrapFindWithin2d<Point3d, LineString2d>();
396  wrapFindWithin2d<Point3d, BasicLineString2d>();
397  wrapFindWithin2d<Point3d, CompoundLineString2d>();
398  wrapFindWithin2d<Point3d, Lanelet>();
399  wrapFindWithin2d<Point3d, Area>();
400  wrapFindWithin3d<Point3d, Point3d>();
401  wrapFindWithin3d<Point3d, BasicPoint3d>();
402  wrapFindWithin3d<Point3d, BoundingBox3d>();
403  wrapFindWithin3d<Point3d, Polygon3d>();
404  wrapFindWithin3d<Point3d, BasicPolygon3d>();
405  wrapFindWithin3d<Point3d, LineString3d>();
406  wrapFindWithin3d<Point3d, BasicLineString3d>();
407  wrapFindWithin3d<Point3d, CompoundLineString3d>();
408  wrapFindWithin3d<Point3d, Lanelet>();
409  wrapFindWithin3d<Point3d, Area>();
410 
411  // linestring layer
412  wrapFindWithin2d<LineString3d, Point2d>();
413  wrapFindWithin2d<LineString3d, BasicPoint2d>();
414  wrapFindWithin2d<LineString3d, BoundingBox2d>();
415  wrapFindWithin2d<LineString3d, Polygon2d>();
416  wrapFindWithin2d<LineString3d, BasicPolygon2d>();
417  wrapFindWithin2d<LineString3d, LineString2d>();
418  wrapFindWithin2d<LineString3d, Lanelet>();
419  wrapFindWithin2d<LineString3d, Area>();
420  wrapFindWithin2d<LineString3d, BasicLineString2d>();
421  wrapFindWithin2d<LineString3d, CompoundLineString2d>();
422  wrapFindWithin3d<LineString3d, Point3d>();
423  wrapFindWithin3d<LineString3d, BasicPoint3d>();
424 
425  // polygon layer
426  wrapFindWithin2d<Polygon3d, Point2d>();
427  wrapFindWithin2d<Polygon3d, BasicPoint2d>();
428  wrapFindWithin2d<Polygon3d, BoundingBox2d>();
429  wrapFindWithin2d<Polygon3d, Polygon2d>();
430  wrapFindWithin2d<Polygon3d, BasicPolygon2d>();
431  wrapFindWithin2d<Polygon3d, LineString2d>();
432  wrapFindWithin2d<Polygon3d, BasicLineString2d>();
433  wrapFindWithin2d<Polygon3d, CompoundLineString2d>();
434  wrapFindWithin2d<Polygon3d, Lanelet>();
435  wrapFindWithin2d<Polygon3d, Area>();
436  wrapFindWithin3d<Polygon3d, Point3d>();
437  wrapFindWithin3d<Polygon3d, BasicPoint3d>();
438 
439  // lanelet layer
440  wrapFindWithin2d<Lanelet, Point2d>();
441  wrapFindWithin2d<Lanelet, BasicPoint2d>();
442  wrapFindWithin2d<Lanelet, BoundingBox2d>();
443  wrapFindWithin2d<Lanelet, Polygon2d>();
444  wrapFindWithin2d<Lanelet, BasicPolygon2d>();
445  wrapFindWithin2d<Lanelet, LineString2d>();
446  wrapFindWithin2d<Lanelet, BasicLineString2d>();
447  wrapFindWithin2d<Lanelet, CompoundLineString2d>();
448  wrapFindWithin2d<Lanelet, Lanelet>();
449  wrapFindWithin2d<Lanelet, Area>();
450  wrapFindWithin3d<Lanelet, Point3d>();
451  wrapFindWithin3d<Lanelet, BasicPoint3d>();
452 
453  // area layer
454  wrapFindWithin2d<Area, Point2d>();
455  wrapFindWithin2d<Area, BasicPoint2d>();
456  wrapFindWithin2d<Area, BoundingBox2d>();
457  wrapFindWithin2d<Area, Polygon2d>();
458  wrapFindWithin2d<Area, BasicPolygon2d>();
459  wrapFindWithin2d<Area, LineString2d>();
460  wrapFindWithin2d<Area, BasicLineString2d>();
461  wrapFindWithin2d<Area, CompoundLineString2d>();
462  wrapFindWithin2d<Area, Lanelet>();
463  wrapFindWithin2d<Area, Area>();
464  wrapFindWithin3d<Area, Point3d>();
465  wrapFindWithin3d<Area, BasicPoint3d>();
466 
467  // boost::geometry functions for convenience
468  def(
469  "intersection", +[](const BasicLineString2d& ls1, const BasicLineString2d& ls2) {
470  BasicPoints2d pts;
471  boost::geometry::intersection(ls1, ls2, pts);
472  return toBasicVector(pts);
473  });
474 
475  def(
476  "intersection", +[](const CompoundLineString2d& ls1, const ConstLineString2d& ls2) {
477  BasicPoints2d pts;
478  boost::geometry::intersection(ls1.basicLineString(), ls2.basicLineString(), pts);
479  return toBasicVector(pts);
480  });
481 
482  def(
483  "intersection", +[](const CompoundLineString2d& ls1, const CompoundLineString2d& ls2) {
484  BasicPoints2d pts;
485  boost::geometry::intersection(ls1.basicLineString(), ls2.basicLineString(), pts);
486  return toBasicVector(pts);
487  });
488 
489  def(
490  "intersection", +[](const ConstLineString2d& ls1, const ConstLineString2d& ls2) {
491  BasicPoints2d pts;
492  boost::geometry::intersection(ls1.basicLineString(), ls2.basicLineString(), pts);
493  return toBasicVector(pts);
494  });
495 }
std::vector< CompoundLineString2d > CompoundLineStrings2d
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > BasicPoints2d
std::vector< LineString2d > LineStrings2d
BasicPoint p
object to2D(object o)
Definition: geometry.cpp:88
std::vector< BasicPoint2d > toBasicVector(const BasicPoints2d &pts)
Definition: geometry.cpp:51
BasicLineString basicLineString() const
Eigen::Vector3d BasicPoint3d
lanelet::BoundingBox3d boundingBox3dFor(const T &t)
Definition: geometry.cpp:61
auto wrapFindWithin2d()
Definition: geometry.cpp:35
#define TO2D_AS(X)
Definition: geometry.cpp:66
object to3D(object o)
Definition: geometry.cpp:102
py::to_python_converter< T, VectorToList< T > > VectorToListConverter
Definition: converter.h:219
auto findWithin3d(LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>>
BasicPoint p2
Eigen::AlignedBox3d BoundingBox3d
auto wrapFindNearest()
Definition: geometry.cpp:26
BoundingBox3d boundingBox3d(const RegulatoryElement &regElem)
BasicLineString basicLineString() const noexcept
BasicPoints2d BasicLineString2d
auto findWithin2d(LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>>
Optional< double > distance
auto wrapFindWithin3d()
Definition: geometry.cpp:43
std::vector< ConstLineString2d > ConstLineStrings2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
std::vector< std::pair< double, PrimT > > findNearest(PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count)
BasicPoint p1
double distancePointToLss(const PtT &p, const object &lss)
Definition: geometry.cpp:78
BoundingBox2d boundingBox2d(const RegulatoryElement &regElem)
std::vector< ConstHybridLineString2d > ConstHybridLineStrings2d
lanelet::BoundingBox2d boundingBox2dFor(const T &t)
Definition: geometry.cpp:56
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: geometry.cpp:118
#define TO3D_AS(X)
Definition: geometry.cpp:72


lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:59