Go to the documentation of this file.
5 #if BOOST_VERSION > 105800
6 #include <boost/geometry/algorithms/relate.hpp>
8 #include <boost/geometry/algorithms/detail/relate/relate.hpp>
15 struct GetGeometry<T,
IfPoly<T, void>> {
29 template <
typename Polygon3dT>
31 const Polygon3dT& l2) {
32 static_assert(traits::is3D<Polygon3dT>(),
"Please call this function with a 3D type!");
36 template <
typename Polygon3dT>
38 static_assert(traits::is3D<Polygon3dT>(),
"Please call this function with a 3D type!");
40 return (projPoint.first - projPoint.second).norm();
43 template <
typename PolygonT>
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) {
56 template <
typename Polygon2dT>
58 static_assert(traits::is2D<Polygon2dT>(),
"Please call this function with a 2D type!");
62 #if BOOST_VERSION > 105800
63 using Mask = boost::geometry::de9im::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>;
66 using Mask = boost::geometry::detail::relate::static_mask<'T', '*', '*', '*', '*', '*', '*', '*', '*'>;
71 template <
typename Polygon3dT>
73 static_assert(traits::is3D<Polygon3dT>(),
"Please call this function with a 3D type!");
78 return std::abs(points.first.z() - points.second.z()) < heightTolerance;
81 template <
typename Polygon2dT>
83 static_assert(traits::is2D<Polygon2dT>(),
"Please call this function with a 2D type!");
87 template <
typename Polygon2dT>
89 static_assert(traits::is2D<Polygon2dT>(),
"Please call this function with a 2D type!");
IfPoly< Polygon3dT, std::pair< BasicPoint3d, BasicPoint3d > > projectedBorderPoint3d(const Polygon3dT &l1, const Polygon3dT &l2)
IfPoly< BasicPolygon2d, BasicPolygons2d > convexPartition< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into convex parts.
static auto threeD(const T &geometry)
std::enable_if_t< traits::isPolygonT< PolygonT >), BasicPolygon3d > toBasicPolygon3d(const PolygonT &t)
static auto twoD(const T &geometry)
std::vector< BasicPolygon2d > BasicPolygons2d
BoundingBox2d to2D(const BoundingBox3d &primitive)
IfPoly< BasicPolygon2d, IndexedTriangles > triangulate< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into triangles.
IfPoly< Polygon3dT, double > distanceToBorder3d(const Polygon3dT &poly1, const Polygon3dT &poly2)
computes the distance of the outer bounds of two polygons in 3d.
Polygon with access to primitive points.
constexpr auto toHybrid(const LineStringT ls)
IndexedTriangles triangulate(const BasicPolygon2d &poly)
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
std::pair< BasicPoint3d, BasicPoint3d > projectedBorderPoint3d(const ConstHybridPolygon3d &l1, const ConstHybridPolygon3d &l2)
IfPoly< Polygon2dT, IndexedTriangles > triangulate(const Polygon2dT &poly)
Split a concave polygon into triangles.
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
IfPoly< Polygon2dT, BasicPolygons2d > convexPartition(const Polygon2dT &poly)
Split a concave polygon into convex parts.
std::vector< IndexedTriangle > IndexedTriangles
std::enable_if_t< traits::isPolygonT< T >(), RetT > IfPoly
std::enable_if_t< traits::isPolygonT< PolygonT >), BasicPolygon2d > toBasicPolygon2d(const PolygonT &t)
BasicPolygons2d convexPartition(const BasicPolygon2d &poly)
auto find(ContainerT &&c, const ValueT &val)
Primitive 2d polygon with basic points.
Combines multiple linestrings to one polygon in 3d that returns BasicPoint3d.
BoundingBox3d to3D(const BoundingBox2d &primitive)
IfPoly< PolygonT, bool > touches2d(const PolygonT &poly1, const PolygonT &poly2)
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52