geometry/impl/Polygon.h
Go to the documentation of this file.
1 #pragma once
5 #if BOOST_VERSION > 105800
6 #include <boost/geometry/algorithms/relate.hpp>
7 #else
8 #include <boost/geometry/algorithms/detail/relate/relate.hpp>
9 #endif
10 
11 namespace lanelet {
12 namespace geometry {
13 namespace internal {
14 template <typename T>
15 struct GetGeometry<T, IfPoly<T, void>> {
16  static inline auto twoD(const T& geometry) { return traits::toBasicPolygon2d(geometry); }
17  static inline auto threeD(const T& geometry) { return traits::toBasicPolygon3d(geometry); }
18 };
19 
20 std::pair<BasicPoint3d, BasicPoint3d> projectedBorderPoint3d(const ConstHybridPolygon3d& l1,
21  const ConstHybridPolygon3d& l2);
22 
23 std::pair<BasicPoint3d, BasicPoint3d> projectedBorderPoint3d(const CompoundHybridPolygon3d& l1,
24  const CompoundHybridPolygon3d& l2);
27 } // namespace internal
28 
29 template <typename Polygon3dT>
31  const Polygon3dT& l2) {
32  static_assert(traits::is3D<Polygon3dT>(), "Please call this function with a 3D type!");
34 }
35 
36 template <typename Polygon3dT>
37 IfPoly<Polygon3dT, double> distanceToBorder3d(const Polygon3dT& poly1, const Polygon3dT& poly2) {
38  static_assert(traits::is3D<Polygon3dT>(), "Please call this function with a 3D type!");
40  return (projPoint.first - projPoint.second).norm();
41 }
42 
43 template <typename PolygonT>
44 IfPoly<PolygonT, bool> touches2d(const PolygonT& poly1, const PolygonT& poly2) {
45  auto rotatedNext = [&](auto iter) { return iter + 1 == poly2.end() ? poly2.begin() : iter + 1; };
46  for (auto i = 0u; i < poly1.numSegments(); ++i) {
47  auto segment = poly1.segment(i);
48  auto second = std::find(poly2.begin(), poly2.end(), segment.second);
49  if (second != poly2.end() && *rotatedNext(second) == segment.first) {
50  return true;
51  }
52  }
53  return false;
54 }
55 
56 template <typename Polygon2dT>
57 IfPoly<Polygon2dT, bool> overlaps2d(const Polygon2dT& poly1, const Polygon2dT& poly2) {
58  static_assert(traits::is2D<Polygon2dT>(), "Please call this function with a 2D type!");
59  if (touches2d(poly1, poly2)) {
60  return false;
61  }
62 #if BOOST_VERSION > 105800
63  using Mask = boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>;
64  return boost::geometry::relate(utils::toHybrid(poly1), utils::toHybrid(poly2), Mask());
65 #else
66  using Mask = boost::geometry::detail::relate::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>;
67  return boost::geometry::detail::relate::relate<Mask>(utils::toHybrid(poly1), utils::toHybrid(poly2));
68 #endif
69 }
70 
71 template <typename Polygon3dT>
72 IfPoly<Polygon3dT, bool> overlaps3d(const Polygon3dT& poly1, const Polygon3dT& poly2, double heightTolerance) {
73  static_assert(traits::is3D<Polygon3dT>(), "Please call this function with a 3D type!");
74  if (!overlaps2d(traits::to2D(poly1), traits::to2D(poly2))) {
75  return false;
76  }
77  auto points = projectedBorderPoint3d(poly1, poly2);
78  return std::abs(points.first.z() - points.second.z()) < heightTolerance;
79 }
80 
81 template <typename Polygon2dT>
83  static_assert(traits::is2D<Polygon2dT>(), "Please call this function with a 2D type!");
84  return internal::convexPartition(BasicPolygon2d(poly.basicBegin(), poly.basicEnd()));
85 }
86 
87 template <typename Polygon2dT>
89  static_assert(traits::is2D<Polygon2dT>(), "Please call this function with a 2D type!");
90  return internal::triangulate(BasicPolygon2d(poly.basicBegin(), poly.basicEnd()));
91 }
92 
93 template <>
95  return internal::convexPartition(poly);
96 }
97 
98 template <>
100  return internal::triangulate(poly);
101 }
102 
103 } // namespace geometry
104 } // namespace lanelet
lanelet::geometry::projectedBorderPoint3d
IfPoly< Polygon3dT, std::pair< BasicPoint3d, BasicPoint3d > > projectedBorderPoint3d(const Polygon3dT &l1, const Polygon3dT &l2)
Definition: geometry/impl/Polygon.h:30
lanelet::geometry::convexPartition< BasicPolygon2d >
IfPoly< BasicPolygon2d, BasicPolygons2d > convexPartition< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into convex parts.
Definition: geometry/impl/Polygon.h:94
lanelet::geometry::internal::GetGeometry< T, IfPoly< T, void > >::threeD
static auto threeD(const T &geometry)
Definition: geometry/impl/Polygon.h:17
lanelet::traits::toBasicPolygon3d
std::enable_if_t< traits::isPolygonT< PolygonT >), BasicPolygon3d > toBasicPolygon3d(const PolygonT &t)
Definition: primitives/Polygon.h:415
lanelet::geometry::internal::GetGeometry< T, IfPoly< T, void > >::twoD
static auto twoD(const T &geometry)
Definition: geometry/impl/Polygon.h:16
lanelet::BasicPolygons2d
std::vector< BasicPolygon2d > BasicPolygons2d
Definition: Forward.h:153
lanelet::traits::to2D
BoundingBox2d to2D(const BoundingBox3d &primitive)
Definition: primitives/BoundingBox.h:304
lanelet
Definition: Attribute.h:13
lanelet::geometry::triangulate< BasicPolygon2d >
IfPoly< BasicPolygon2d, IndexedTriangles > triangulate< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into triangles.
Definition: geometry/impl/Polygon.h:99
lanelet::geometry::distanceToBorder3d
IfPoly< Polygon3dT, double > distanceToBorder3d(const Polygon3dT &poly1, const Polygon3dT &poly2)
computes the distance of the outer bounds of two polygons in 3d.
Definition: geometry/impl/Polygon.h:37
lanelet::ConstHybridPolygon3d
Polygon with access to primitive points.
Definition: primitives/Polygon.h:228
lanelet::traits::toHybrid
constexpr auto toHybrid(const LineStringT ls)
Definition: primitives/LineString.h:765
Point.h
lanelet::geometry::internal::triangulate
IndexedTriangles triangulate(const BasicPolygon2d &poly)
Definition: PolygonTriangulationGeometry.cpp:454
LineString.h
lanelet::geometry::overlaps2d
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
Definition: geometry/impl/Area.h:43
lanelet::geometry::internal::projectedBorderPoint3d
std::pair< BasicPoint3d, BasicPoint3d > projectedBorderPoint3d(const ConstHybridPolygon3d &l1, const ConstHybridPolygon3d &l2)
Definition: LineStringGeometry.cpp:407
lanelet::geometry::triangulate
IfPoly< Polygon2dT, IndexedTriangles > triangulate(const Polygon2dT &poly)
Split a concave polygon into triangles.
Definition: geometry/impl/Polygon.h:88
lanelet::geometry::overlaps3d
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
Definition: geometry/impl/Area.h:48
lanelet::geometry::convexPartition
IfPoly< Polygon2dT, BasicPolygons2d > convexPartition(const Polygon2dT &poly)
Split a concave polygon into convex parts.
Definition: geometry/impl/Polygon.h:82
lanelet::geometry::IndexedTriangles
std::vector< IndexedTriangle > IndexedTriangles
Definition: geometry/Polygon.h:319
lanelet::IfPoly
std::enable_if_t< traits::isPolygonT< T >(), RetT > IfPoly
Definition: primitives/Polygon.h:428
lanelet::traits::toBasicPolygon2d
std::enable_if_t< traits::isPolygonT< PolygonT >), BasicPolygon2d > toBasicPolygon2d(const PolygonT &t)
Definition: primitives/Polygon.h:398
lanelet::geometry::internal::convexPartition
BasicPolygons2d convexPartition(const BasicPolygon2d &poly)
Definition: PolygonTriangulationGeometry.cpp:453
Polygon.h
lanelet::utils::find
auto find(ContainerT &&c, const ValueT &val)
Definition: Utilities.h:186
lanelet::BasicPolygon2d
Primitive 2d polygon with basic points.
Definition: primitives/Polygon.h:18
lanelet::CompoundHybridPolygon3d
Combines multiple linestrings to one polygon in 3d that returns BasicPoint3d.
Definition: CompoundPolygon.h:100
lanelet::traits::to3D
BoundingBox3d to3D(const BoundingBox2d &primitive)
Definition: primitives/BoundingBox.h:303
lanelet::geometry::touches2d
IfPoly< PolygonT, bool > touches2d(const PolygonT &poly1, const PolygonT &poly2)
Definition: geometry/impl/Polygon.h:44


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52