2 #include <boost/geometry/geometries/register/ring.hpp> 33 static const order_selector value = clockwise;
37 static const closure_selector value = open;
42 struct point_order<
lanelet::ConstPolygon3d> {
43 static const order_selector value = clockwise;
47 static const closure_selector value = open;
53 static const order_selector value = clockwise;
57 static const closure_selector value = open;
62 struct point_order<
lanelet::ConstPolygon2d> {
63 static const order_selector value = clockwise;
67 static const closure_selector value = open;
72 struct point_order<
lanelet::BasicPolygon2d> {
73 static const order_selector value = clockwise;
77 static const closure_selector value = open;
82 struct point_order<
lanelet::BasicPolygon3d> {
83 static const order_selector value = clockwise;
87 static const closure_selector value = open;
92 struct point_order<
lanelet::ConstHybridPolygon2d> {
93 static const order_selector value = clockwise;
96 struct closure<
lanelet::ConstHybridPolygon2d> {
97 static const closure_selector value = open;
102 struct point_order<
lanelet::ConstHybridPolygon3d> {
103 static const order_selector value = clockwise;
106 struct closure<
lanelet::ConstHybridPolygon3d> {
107 static const closure_selector value = open;
111 struct point_order<
lanelet::CompoundHybridPolygon2d> {
112 static const order_selector value = clockwise;
115 struct closure<
lanelet::CompoundHybridPolygon2d> {
116 static const closure_selector value = open;
121 struct point_order<
lanelet::CompoundHybridPolygon3d> {
122 static const order_selector value = clockwise;
125 struct closure<
lanelet::CompoundHybridPolygon3d> {
126 static const closure_selector value = open;
131 struct point_order<
lanelet::CompoundPolygon2d> {
132 static const order_selector value = clockwise;
136 static const closure_selector value = open;
141 struct point_order<
lanelet::CompoundPolygon3d> {
142 static const order_selector value = clockwise;
146 static const closure_selector value = open;
231 using boost::geometry::area;
232 using boost::geometry::within;
240 template <
typename Polygon3dT>
241 IfPoly<Polygon3dT, double>
distanceToBorder3d(
const Polygon3dT& poly1,
const Polygon3dT& poly2);
248 template <
typename Polygon3dT>
249 IfPoly<Polygon3dT, BoundingBox3d>
boundingBox3d(
const Polygon3dT& polygon);
251 template <
typename Polygon2dT>
252 IfPoly<Polygon2dT, BoundingBox2d>
boundingBox2d(
const Polygon2dT& polygon);
254 template <
typename Polygon3dT>
256 static_assert(traits::is3D<Polygon3dT>(),
"Please call this function with a 3D type!");
258 for (
const auto&
p : polygon) {
264 template <
typename Polygon2dT>
266 static_assert(traits::is2D<Polygon2dT>(),
"Please call this function with a 2D type!");
268 for (
const auto&
p : polygon) {
274 template <
typename Polygon3dT>
276 const Polygon3dT& l2);
278 template <
typename PolygonT>
281 template <
typename Polygon2dT>
284 template <
typename Polygon3dT>
299 template <
typename Polygon2dT>
327 template <
typename Polygon2dT>
Polygon with access to primitive points.
lanelet::BasicPolygons2d & type
A (basic) 2d polygon with holes insideThis class is thought for geometry calculations, it has no properties of a normal lanelet primitive.
An mutable clockwise oriented, open (ie start point != end point) polygon in 2d.
An immutable clockwise oriented, open (ie start point != end point) polygon in 2d.
Combines multiple linestrings to one polygon in 3d that returns BasicPoint3d.
IfPoly< Polygon3dT, double > distanceToBorder3d(const Polygon3dT &poly1, const Polygon3dT &poly2)
computes the distance of the outer bounds of two polygons in 3d.
Primitive 2d polygon with basic points.
std::array< size_t, 3 > IndexedTriangle
Combines multiple linestrings to one polygon in 3d.
Eigen::AlignedBox3d BoundingBox3d
Convenience type for an axis aligned bounding box in 3d.
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
IndexedTriangles triangulate(const BasicPolygon2d &poly)
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
Polygon with access to primitive points.
A (basic) 2d polygon with holes insideThis class is thought for geometry calculations, it has no properties of a normal lanelet primitive.
Axis-Aligned bounding box in 2d.
std::pair< BasicPoint3d, BasicPoint3d > projectedBorderPoint3d(const ConstHybridPolygon3d &l1, const ConstHybridPolygon3d &l2)
A mutable clockwise oriented, open (ie start point != end point) polygon in 3d.
An immutable clockwise oriented, open (ie start point != end point) polygon in 3d.
std::vector< BasicPolygon3d > BasicPolygons3d
Combines multiple linestrings to one polygon in 2d that returns BasicPoint2d.
auto toBasicPoint(const PointT &point) -> std::enable_if_t< PointTraits< PointT >::IsPrimitive, BasicPointT< PointT >>
std::vector< IndexedTriangle > IndexedTriangles
std::enable_if_t< traits::isPolygonT< T >(), RetT > IfPoly
BasicPolygons2d convexPartition(const BasicPolygon2d &poly)
IfPoly< PolygonT, bool > touches2d(const PolygonT &poly1, const PolygonT &poly2)
lanelet::BasicPolygons3d & type
BoundingBox2d & extend(const Eigen::MatrixBase< Derived > &p)
Primitive 3d polygon with basic points.
Combines multiple linestrings to one polygon in 2d.
IfPoly< Polygon2dT, BoundingBox2d > boundingBox2d(const Polygon2dT &polygon)
IfPoly< BasicPolygon2d, BasicPolygons2d > convexPartition< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into convex parts.
const lanelet::BasicPolygons2d & type
IfPoly< BasicPolygon2d, IndexedTriangles > triangulate< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into triangles.
const lanelet::BasicPolygons3d & type
IfPoly< Polygon3dT, BoundingBox3d > boundingBox3d(const Polygon3dT &polygon)
std::vector< BasicPolygon2d > BasicPolygons2d