geometry/Polygon.h
Go to the documentation of this file.
1 #pragma once
2 #include <boost/geometry/geometries/register/ring.hpp>
3 
7 
8 /***********************************************************************
9  * BOOST GEOMETRY REGISTRATIONS *
10  ***********************************************************************/
11 
12 // Register our Polygons
13 BOOST_GEOMETRY_REGISTER_RING(lanelet::Polygon3d)
14 BOOST_GEOMETRY_REGISTER_RING(lanelet::ConstPolygon3d)
15 BOOST_GEOMETRY_REGISTER_RING(lanelet::Polygon2d)
16 BOOST_GEOMETRY_REGISTER_RING(lanelet::ConstPolygon2d)
17 BOOST_GEOMETRY_REGISTER_RING(lanelet::BasicPolygon2d)
18 BOOST_GEOMETRY_REGISTER_RING(lanelet::BasicPolygon3d)
19 BOOST_GEOMETRY_REGISTER_RING(lanelet::ConstHybridPolygon2d)
20 BOOST_GEOMETRY_REGISTER_RING(lanelet::ConstHybridPolygon3d)
21 BOOST_GEOMETRY_REGISTER_RING(lanelet::CompoundPolygon2d)
22 BOOST_GEOMETRY_REGISTER_RING(lanelet::CompoundPolygon3d)
23 BOOST_GEOMETRY_REGISTER_RING(lanelet::CompoundHybridPolygon2d)
24 BOOST_GEOMETRY_REGISTER_RING(lanelet::CompoundHybridPolygon3d)
25 
26 // traits for boost::geometry. All lanelet polygons are open and clockwise.
27 namespace boost {
28 namespace geometry {
29 namespace traits {
30 // traits for lanelet::Polygon
31 template <>
32 struct point_order<lanelet::Polygon3d> {
33  static const order_selector value = clockwise;
34 };
35 template <>
36 struct closure<lanelet::Polygon3d> {
37  static const closure_selector value = open;
38 };
39 
40 // traits for lanelet::ConstPolygon
41 template <>
42 struct point_order<lanelet::ConstPolygon3d> {
43  static const order_selector value = clockwise;
44 };
45 template <>
46 struct closure<lanelet::ConstPolygon3d> {
47  static const closure_selector value = open;
48 };
49 
50 // traits for lanelet::Polygon2d
51 template <>
52 struct point_order<lanelet::Polygon2d> {
53  static const order_selector value = clockwise;
54 };
55 template <>
56 struct closure<lanelet::Polygon2d> {
57  static const closure_selector value = open;
58 };
59 
60 // traits for lanelet::ConstPolygon2d
61 template <>
62 struct point_order<lanelet::ConstPolygon2d> {
63  static const order_selector value = clockwise;
64 };
65 template <>
66 struct closure<lanelet::ConstPolygon2d> {
67  static const closure_selector value = open;
68 };
69 
70 // traits for lanelet::BasicPolygon2d
71 template <>
72 struct point_order<lanelet::BasicPolygon2d> {
73  static const order_selector value = clockwise;
74 };
75 template <>
76 struct closure<lanelet::BasicPolygon2d> {
77  static const closure_selector value = open;
78 };
79 
80 // traits for lanelet::BasicPolygon3d
81 template <>
82 struct point_order<lanelet::BasicPolygon3d> {
83  static const order_selector value = clockwise;
84 };
85 template <>
86 struct closure<lanelet::BasicPolygon3d> {
87  static const closure_selector value = open;
88 };
89 
90 // traits for lanelet::ConstHybridPolygon2d
91 template <>
92 struct point_order<lanelet::ConstHybridPolygon2d> {
93  static const order_selector value = clockwise;
94 };
95 template <>
96 struct closure<lanelet::ConstHybridPolygon2d> {
97  static const closure_selector value = open;
98 };
99 
100 // traits for lanelet::ConstHybridPolygon
101 template <>
102 struct point_order<lanelet::ConstHybridPolygon3d> {
103  static const order_selector value = clockwise;
104 };
105 template <>
106 struct closure<lanelet::ConstHybridPolygon3d> {
107  static const closure_selector value = open;
108 };
109 // traits for lanelet::CompoundHybridPolygon2d
110 template <>
111 struct point_order<lanelet::CompoundHybridPolygon2d> {
112  static const order_selector value = clockwise;
113 };
114 template <>
115 struct closure<lanelet::CompoundHybridPolygon2d> {
116  static const closure_selector value = open;
117 };
118 
119 // traits for lanelet::CompoundHybridPolygon3d
120 template <>
121 struct point_order<lanelet::CompoundHybridPolygon3d> {
122  static const order_selector value = clockwise;
123 };
124 template <>
125 struct closure<lanelet::CompoundHybridPolygon3d> {
126  static const closure_selector value = open;
127 };
128 
129 // traits for lanelet::CompoundPolygon2d
130 template <>
131 struct point_order<lanelet::CompoundPolygon2d> {
132  static const order_selector value = clockwise;
133 };
134 template <>
135 struct closure<lanelet::CompoundPolygon2d> {
136  static const closure_selector value = open;
137 };
138 
139 // traits for lanelet::CompoundPolygon3d
140 template <>
141 struct point_order<lanelet::CompoundPolygon3d> {
142  static const order_selector value = clockwise;
143 };
144 template <>
145 struct closure<lanelet::CompoundPolygon3d> {
146  static const closure_selector value = open;
147 };
148 
149 // traits for BasicPolygonWithHoles3d to register as a boost::polygon (taken
150 // from
151 // http://www.boost.org/doc/libs/1_58_0/libs/geometry/doc/html/geometry/examples/example_source_code__adapting_a_legacy_geometry_object_model.html)
153 template <>
154 struct tag<LLPolygon3d> {
155  using type = polygon_tag; // NOLINT
156 };
157 template <>
158 struct ring_const_type<LLPolygon3d> {
159  using type = const lanelet::BasicPolygon3d&; // NOLINT
160 };
161 template <>
162 struct ring_mutable_type<LLPolygon3d> {
163  using type = lanelet::BasicPolygon3d&; // NOLINT
164 };
165 template <>
166 struct interior_const_type<LLPolygon3d> {
167  using type = const lanelet::BasicPolygons3d&; // NOLINT
168 };
169 template <>
170 struct interior_mutable_type<LLPolygon3d> {
171  using type = lanelet::BasicPolygons3d&; // NOLINT
172 };
173 
174 template <>
175 struct exterior_ring<LLPolygon3d> {
176  static lanelet::BasicPolygon3d& get(LLPolygon3d& p) { return p.outer; }
177  static const lanelet::BasicPolygon3d& get(LLPolygon3d const& p) { return p.outer; }
178 };
179 
180 template <>
181 struct interior_rings<LLPolygon3d> {
182  static lanelet::BasicPolygons3d& get(LLPolygon3d& p) { return p.inner; }
183  static const lanelet::BasicPolygons3d& get(LLPolygon3d const& p) { return p.inner; }
184 };
185 
186 // traits for BasicPolygonWithHoles2d to register as a boost::polygon (taken
187 // from
188 // http://www.boost.org/doc/libs/1_58_0/libs/geometry/doc/html/geometry/examples/example_source_code__adapting_a_legacy_geometry_object_model.html)
190 template <>
191 struct tag<LLPolygon2d> {
192  using type = polygon_tag; // NOLINT
193 };
194 template <>
195 struct ring_const_type<LLPolygon2d> {
196  using type = const lanelet::BasicPolygon2d&; // NOLINT
197 };
198 template <>
199 struct ring_mutable_type<LLPolygon2d> {
200  using type = lanelet::BasicPolygon2d&; // NOLINT
201 };
202 template <>
203 struct interior_const_type<LLPolygon2d> {
204  using type = const lanelet::BasicPolygons2d&; // NOLINT
205 };
206 template <>
207 struct interior_mutable_type<LLPolygon2d> {
208  using type = lanelet::BasicPolygons2d&; // NOLINT
209 };
210 
211 template <>
212 struct exterior_ring<LLPolygon2d> {
213  static lanelet::BasicPolygon2d& get(LLPolygon2d& p) { return p.outer; }
214  static const lanelet::BasicPolygon2d& get(LLPolygon2d const& p) { return p.outer; }
215 };
216 
217 template <>
218 struct interior_rings<LLPolygon2d> {
219  static lanelet::BasicPolygons2d& get(LLPolygon2d& p) { return p.inner; }
220  static const lanelet::BasicPolygons2d& get(LLPolygon2d const& p) { return p.inner; }
221 };
222 } // namespace traits
223 } // namespace geometry
224 } // namespace boost
225 
226 /***********************************************************************
227  * ALGORITHMS *
228  ***********************************************************************/
229 namespace lanelet {
230 namespace geometry {
231 using boost::geometry::area;
232 using boost::geometry::within;
233 
240 template <typename Polygon3dT>
241 IfPoly<Polygon3dT, double> distanceToBorder3d(const Polygon3dT& poly1, const Polygon3dT& poly2);
242 
248 template <typename Polygon3dT>
249 IfPoly<Polygon3dT, BoundingBox3d> boundingBox3d(const Polygon3dT& polygon);
250 
251 template <typename Polygon2dT>
252 IfPoly<Polygon2dT, BoundingBox2d> boundingBox2d(const Polygon2dT& polygon);
253 
254 template <typename Polygon3dT>
256  static_assert(traits::is3D<Polygon3dT>(), "Please call this function with a 3D type!");
257  BoundingBox3d bb;
258  for (const auto& p : polygon) {
259  bb.extend(traits::toBasicPoint(p));
260  }
261  return bb;
262 }
263 
264 template <typename Polygon2dT>
266  static_assert(traits::is2D<Polygon2dT>(), "Please call this function with a 2D type!");
267  BoundingBox2d bb;
268  for (const auto& p : polygon) {
270  }
271  return bb;
272 }
273 
274 template <typename Polygon3dT>
276  const Polygon3dT& l2);
277 
278 template <typename PolygonT>
279 IfPoly<PolygonT, bool> touches2d(const PolygonT& poly1, const PolygonT& poly2);
280 
281 template <typename Polygon2dT>
282 IfPoly<Polygon2dT, bool> overlaps2d(const Polygon2dT& poly1, const Polygon2dT& poly2);
283 
284 template <typename Polygon3dT>
285 IfPoly<Polygon3dT, bool> overlaps3d(const Polygon3dT& poly1, const Polygon3dT& poly2, double heightTolerance);
286 
299 template <typename Polygon2dT>
312 template <>
314 using IndexedTriangle = std::array<size_t, 3>;
315 using IndexedTriangles = std::vector<IndexedTriangle>;
316 
327 template <typename Polygon2dT>
328 IfPoly<Polygon2dT, IndexedTriangles> triangulate(const Polygon2dT& poly);
338 template <>
340 
341 } // namespace geometry
342 } // namespace lanelet
343 
344 #include "impl/Polygon.h"
Polygon with access to primitive points.
BasicPoint p
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
Definition: Forward.h:154
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 >>
Definition: Traits.h:165
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)
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.
IfPoly< BasicPolygon2d, IndexedTriangles > triangulate< BasicPolygon2d >(const BasicPolygon2d &poly)
Split a concave polygon into triangles.
IfPoly< Polygon3dT, BoundingBox3d > boundingBox3d(const Polygon3dT &polygon)
std::vector< BasicPolygon2d > BasicPolygons2d
Definition: Forward.h:153


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32