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> 25 template <
typename PrimT>
27 using ResultT = std::vector<std::pair<double, PrimT>>;
32 return def(
"findNearest", func);
34 template <
typename PrimT,
typename GeometryT>
36 using ResultT = std::vector<std::pair<double, PrimT>>;
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");
42 template <
typename PrimT,
typename GeometryT>
44 using ResultT = std::vector<std::pair<double, PrimT>>;
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");
52 return utils::transform(pts, [](
auto&
p) {
return BasicPoint2d(
p.x(),
p.y()); });
67 if (extract<X>(o).check()) { \ 68 return object(to2D(extract<X>(o)())); \ 73 if (extract<X>(o).check()) { \ 74 return object(to3D(extract<X>(o)())); \ 77 template <
typename PtT>
79 auto distance = [](PtT p,
auto range) {
80 return boost::geometry::distance(p, utils::transform(range, [](
auto& v) {
return utils::toHybrid(v); }));
82 if (extract<ConstLineStrings2d>(lss).check()) {
83 return distance(p, extract<ConstLineStrings2d>(lss)());
85 return distance(p, extract<LineStrings2d>(lss)());
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>);
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>);
147 def(
"distance", lg::distance<ConstHybridLineString2d, ConstHybridLineString2d>);
159 def(
"distance", lg::distance<ConstHybridPolygon2d, BasicPoint2d>);
169 def(
"distance", lg::distance<ConstHybridPolygon2d, ConstHybridLineString2d>);
172 def(
"distance", lg::distance<ConstHybridLineString2d, ConstHybridPolygon2d>);
179 def(
"distance", lg::distance<ConstHybridPolygon2d, ConstHybridPolygon2d>);
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>);
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>);
223 def(
"distanceToLines", distancePointToLss<ConstPoint2d>);
224 def(
"distanceToLines", distancePointToLss<BasicPoint2d>);
225 def(
"distanceToLines", distancePointToLss<ConstPoint2d>);
226 def(
"distanceToLines", distancePointToLss<BasicPoint2d>);
232 "distance", +[](
const HybridLs3d& ls1,
const HybridLs3d& ls2) {
return lg::distance3d(ls1, ls2); });
244 def(
"distance", lg::distance3d<ConstLanelet, BasicPoint3d>);
245 def(
"distance", lg::distance3d<BasicPoint3d, ConstLanelet>);
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>);
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>);
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>);
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>);
288 def(
"area", boost::geometry::area<BasicPolygon2d>);
289 def(
"area", boost::geometry::area<ConstHybridPolygon2d>);
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");
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");
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");
305 def(
"length", lg::length<ConstLineString2d>);
306 def(
"length", lg::length<ConstLineString3d>);
307 def(
"length", lg::length<CompoundLineString2d>);
308 def(
"length", lg::length<CompoundLineString3d>);
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>);
317 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString2d>);
318 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<ConstLineString3d>);
319 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString2d>);
320 def(
"nearestPointAtDistance", lg::nearestPointAtDistance<CompoundLineString3d>);
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");
327 def(
"projectedPoint3d", lg::projectedPoint3d<ConstLineString3d>,
328 "Returns the respective projected points of the closest distance of two " 330 def(
"projectedPoint3d", lg::projectedPoint3d<ConstHybridLineString3d>,
331 "Returns the respective projected points of the closest distance of two " 333 def(
"projectedPoint3d", lg::projectedPoint3d<CompoundLineString3d>,
334 "Returns the respective projected points of the closest distance of two " 335 "compound linestrings");
339 return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
341 def(
"intersects2d", lg::intersects<ConstHybridLineString2d, ConstHybridLineString2d>);
344 return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
348 return lg::intersects(utils::toHybrid(ls1), utils::toHybrid(ls2));
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>);
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.));
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.));
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");
382 wrapFindNearest<Point3d>();
383 wrapFindNearest<LineString3d>();
384 wrapFindNearest<Polygon3d>();
385 wrapFindNearest<Lanelet>();
386 wrapFindNearest<Area>();
387 wrapFindNearest<RegulatoryElementPtr>();
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>();
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>();
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>();
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>();
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>();
471 boost::geometry::intersection(ls1, ls2, pts);
std::vector< CompoundLineString2d > CompoundLineStrings2d
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > BasicPoints2d
std::vector< LineString2d > LineStrings2d
std::vector< BasicPoint2d > toBasicVector(const BasicPoints2d &pts)
BasicLineString basicLineString() const
Eigen::Vector3d BasicPoint3d
lanelet::BoundingBox3d boundingBox3dFor(const T &t)
py::to_python_converter< T, VectorToList< T > > VectorToListConverter
auto findWithin3d(LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>>
Eigen::AlignedBox3d BoundingBox3d
BoundingBox3d boundingBox3d(const RegulatoryElement ®Elem)
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
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)
double distancePointToLss(const PtT &p, const object &lss)
BoundingBox2d boundingBox2d(const RegulatoryElement ®Elem)
std::vector< ConstHybridLineString2d > ConstHybridLineStrings2d
lanelet::BoundingBox2d boundingBox2dFor(const T &t)
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)