GteConvexHull3.h
Go to the documentation of this file.
1 // David Eberly, Geometric Tools, Redmond WA 98052
2 // Copyright (c) 1998-2017
3 // Distributed under the Boost Software License, Version 1.0.
4 // http://www.boost.org/LICENSE_1_0.txt
5 // http://www.geometrictools.com/License/Boost/LICENSE_1_0.txt
6 // File Version: 3.0.0 (2016/06/19)
7 
8 #pragma once
9 
10 // Compute the convex hull of 3D points using incremental insertion. The only
11 // way to ensure a correct result for the input vertices (assumed to be exact)
12 // is to choose ComputeType for exact rational arithmetic. You may use
13 // BSNumber. No divisions are performed in this computation, so you do not
14 // have to use BSRational.
15 //
16 // The worst-case choices of N for Real of type BSNumber or BSRational with
17 // integer storage UIntegerFP32<N> are listed in the next table. The numerical
18 // computations are encapsulated in PrimalQuery3<Real>::ToPlane. We recommend
19 // using only BSNumber, because no divisions are performed in the convex-hull
20 // computations.
21 //
22 // input type | compute type | N
23 // -----------+--------------+------
24 // float | BSNumber | 27
25 // double | BSNumber | 197
26 // float | BSRational | 2882
27 // double | BSRational | 21688
28 
31 #include <Mathematics/GteLine.h>
33 #include <functional>
34 #include <set>
35 #include <thread>
36 #include <vector>
37 
38 namespace gte
39 {
40 
41 template <typename InputType, typename ComputeType>
43 {
44 public:
45  // The class is a functor to support computing the convex hull of multiple
46  // data sets using the same class object. For multithreading in Update,
47  // choose 'numThreads' subject to the constraints
48  // 1 <= numThreads <= std::thread::hardware_concurrency().
49  ConvexHull3(unsigned int numThreads = 1);
50 
51  // The input is the array of points whose convex hull is required. The
52  // epsilon value is used to determine the intrinsic dimensionality of the
53  // vertices (d = 0, 1, 2, or 3). When epsilon is positive, the
54  // determination is fuzzy--points approximately the same point,
55  // approximately on a line, approximately planar, or volumetric.
56  bool operator()(int numPoints, Vector3<InputType> const* points,
57  InputType epsilon);
58 
59  // Dimensional information. If GetDimension() returns 1, the points lie
60  // on a line P+t*D (fuzzy comparison when epsilon > 0). You can sort
61  // these if you need a polyline output by projecting onto the line each
62  // vertex X = P+t*D, where t = Dot(D,X-P). If GetDimension() returns 2,
63  // the points line on a plane P+s*U+t*V (fuzzy comparison when
64  // epsilon > 0). You can project each point X = P+s*U+t*V, where
65  // s = Dot(U,X-P) and t = Dot(V,X-P), then apply ConvexHull2 to the (s,t)
66  // tuples.
67  inline InputType GetEpsilon() const;
68  inline int GetDimension() const;
69  inline Line3<InputType> const& GetLine() const;
70  inline Plane3<InputType> const& GetPlane() const;
71 
72  // Member access.
73  inline int GetNumPoints() const;
74  inline int GetNumUniquePoints() const;
75  inline Vector3<InputType> const* GetPoints() const;
76  inline PrimalQuery3<ComputeType> const& GetQuery() const;
77 
78  // The convex hull is a convex polyhedron with triangular faces.
79  inline std::vector<TriangleKey<true>> const& GetHullUnordered() const;
80  ETManifoldMesh const& GetHullMesh() const;
81 
82 private:
83  // Support for incremental insertion.
84  void Update(int i);
85 
86  // The epsilon value is used for fuzzy determination of intrinsic
87  // dimensionality. If the dimension is 0, 1, or 2, the constructor
88  // returns early. The caller is responsible for retrieving the dimension
89  // and taking an alternate path should the dimension be smaller than 3.
90  // If the dimension is 0, the caller may as well treat all points[] as a
91  // single point, say, points[0]. If the dimension is 1, the caller can
92  // query for the approximating line and project points[] onto it for
93  // further processing. If the dimension is 2, the caller can query for
94  // the approximating plane and project points[] onto it for further
95  // processing.
96  InputType mEpsilon;
100 
101  // The array of points used for geometric queries. If you want to be
102  // certain of a correct result, choose ComputeType to be BSNumber.
103  std::vector<Vector3<ComputeType>> mComputePoints;
105 
109  std::vector<TriangleKey<true>> mHullUnordered;
111  unsigned int mNumThreads;
112 };
113 
114 
115 template <typename InputType, typename ComputeType>
117  :
118  mEpsilon((InputType)0),
119  mDimension(0),
120  mLine(Vector3<InputType>::Zero(), Vector3<InputType>::Zero()),
121  mPlane(Vector3<InputType>::Zero(), (InputType)0),
122  mNumPoints(0),
123  mNumUniquePoints(0),
124  mPoints(nullptr),
125  mNumThreads(numThreads)
126 {
127 }
128 
129 template <typename InputType, typename ComputeType>
131  Vector3<InputType> const* points, InputType epsilon)
132 {
133  mEpsilon = std::max(epsilon, (InputType)0);
134  mDimension = 0;
135  mLine.origin = Vector3<InputType>::Zero();
136  mLine.direction = Vector3<InputType>::Zero();
137  mPlane.normal = Vector3<InputType>::Zero();
138  mPlane.constant = (InputType)0;
139  mNumPoints = numPoints;
140  mNumUniquePoints = 0;
141  mPoints = points;
142  mHullUnordered.clear();
143  mHullMesh.Clear();
144 
145  int i, j;
146  if (mNumPoints < 4)
147  {
148  // ConvexHull3 should be called with at least four points.
149  return false;
150  }
151 
153  if (info.dimension == 0)
154  {
155  // The set is (nearly) a point.
156  return false;
157  }
158 
159  if (info.dimension == 1)
160  {
161  // The set is (nearly) collinear.
162  mDimension = 1;
163  mLine = Line3<InputType>(info.origin, info.direction[0]);
164  return false;
165  }
166 
167  if (info.dimension == 2)
168  {
169  // The set is (nearly) coplanar.
170  mDimension = 2;
172  info.direction[1]), info.origin);
173  return false;
174  }
175 
176  mDimension = 3;
177 
178  // Compute the vertices for the queries.
179  mComputePoints.resize(mNumPoints);
181  for (i = 0; i < mNumPoints; ++i)
182  {
183  for (j = 0; j < 3; ++j)
184  {
185  mComputePoints[i][j] = points[i][j];
186  }
187  }
188 
189  // Insert the faces of the (nondegenerate) tetrahedron constructed by the
190  // call to GetInformation.
191  if (!info.extremeCCW)
192  {
193  std::swap(info.extreme[2], info.extreme[3]);
194  }
195 
196  mHullUnordered.push_back(TriangleKey<true>(info.extreme[1],
197  info.extreme[2], info.extreme[3]));
198  mHullUnordered.push_back(TriangleKey<true>(info.extreme[0],
199  info.extreme[3], info.extreme[2]));
200  mHullUnordered.push_back(TriangleKey<true>(info.extreme[0],
201  info.extreme[1], info.extreme[3]));
202  mHullUnordered.push_back(TriangleKey<true>(info.extreme[0],
203  info.extreme[2], info.extreme[1]));
204 
205  // Incrementally update the hull. The set of processed points is
206  // maintained to eliminate duplicates, either in the original input
207  // points or in the points obtained by snap rounding.
208  std::set<Vector3<InputType>> processed;
209  for (i = 0; i < 4; ++i)
210  {
211  processed.insert(points[info.extreme[i]]);
212  }
213  for (i = 0; i < mNumPoints; ++i)
214  {
215  if (processed.find(points[i]) == processed.end())
216  {
217  Update(i);
218  processed.insert(points[i]);
219  }
220  }
221  mNumUniquePoints = static_cast<int>(processed.size());
222  return true;
223 }
224 
225 template <typename InputType, typename ComputeType> inline
227 {
228  return mEpsilon;
229 }
230 
231 template <typename InputType, typename ComputeType> inline
233 {
234  return mDimension;
235 }
236 
237 template <typename InputType, typename ComputeType> inline
239 {
240  return mLine;
241 }
242 
243 template <typename InputType, typename ComputeType> inline
245 {
246  return mPlane;
247 }
248 
249 template <typename InputType, typename ComputeType> inline
251 {
252  return mNumPoints;
253 }
254 
255 template <typename InputType, typename ComputeType> inline
257 {
258  return mNumUniquePoints;
259 }
260 
261 template <typename InputType, typename ComputeType> inline
263 {
264  return mPoints;
265 }
266 
267 template <typename InputType, typename ComputeType> inline
269 {
270  return mQuery;
271 }
272 
273 template <typename InputType, typename ComputeType> inline
274 std::vector<TriangleKey<true>> const& ConvexHull3<InputType, ComputeType>::GetHullUnordered() const
275 {
276  return mHullUnordered;
277 }
278 
279 template <typename InputType, typename ComputeType>
281 {
282  // Create the mesh only on demand.
283  if (mHullMesh.GetTriangles().size() == 0)
284  {
285  for (auto const& tri : mHullUnordered)
286  {
287  mHullMesh.Insert(tri.V[0], tri.V[1], tri.V[2]);
288  }
289  }
290 
291  return mHullMesh;
292 }
293 
294 template <typename InputType, typename ComputeType>
296 {
297  // The terminator that separates visible faces from nonvisible faces is
298  // constructed by this code. Visible faces for the incoming hull are
299  // removed, and the boundary of that set of triangles is the terminator.
300  // New visible faces are added using the incoming point and the edges of
301  // the terminator.
302  //
303  // A simple algorithm for computing terminator edges is the following.
304  // Back-facing triangles are located and the three edges are processed.
305  // The first time an edge is visited, insert it into the terminator. If
306  // it is visited a second time, the edge is removed because it is shared
307  // by another back-facing triangle and, therefore, cannot be a terminator
308  // edge. After visiting all back-facing triangles, the only remaining
309  // edges in the map are the terminator edges.
310  //
311  // The order of vertices of an edge is important for adding new faces with
312  // the correct vertex winding. However, the edge "toggle" (insert edge,
313  // remove edge) should use edges with unordered vertices, because the
314  // edge shared by one triangle has opposite ordering relative to that of
315  // the other triangle. The map uses unordered edges as the keys but
316  // stores the ordered edge as the value. This avoids having to look up
317  // an edge twice in a map with ordered edge keys.
318 
319  unsigned int numFaces = static_cast<unsigned int>(mHullUnordered.size());
320  std::vector<int> queryResult(numFaces);
321  if (mNumThreads > 1 && numFaces >= mNumThreads)
322  {
323  // Partition the data for multiple threads.
324  unsigned int numFacesPerThread = numFaces / mNumThreads;
325  std::vector<unsigned int> jmin(mNumThreads), jmax(mNumThreads);
326  for (unsigned int t = 0; t < mNumThreads; ++t)
327  {
328  jmin[t] = t * numFacesPerThread;
329  jmax[t] = jmin[t] + numFacesPerThread - 1;
330  }
331  jmax[mNumThreads - 1] = numFaces - 1;
332 
333  // Execute the point-plane queries in multiple threads.
334  std::vector<std::thread> process(mNumThreads);
335  for (unsigned int t = 0; t < mNumThreads; ++t)
336  {
337  process[t] = std::thread([this, i, t, &jmin, &jmax,
338  &queryResult]()
339  {
340  for (unsigned int j = jmin[t]; j <= jmax[t]; ++j)
341  {
342  TriangleKey<true> const& tri = mHullUnordered[j];
343  queryResult[j] = mQuery.ToPlane(i, tri.V[0], tri.V[1], tri.V[2]);
344  }
345  });
346  }
347 
348  // Wait for all threads to finish.
349  for (unsigned int t = 0; t < mNumThreads; ++t)
350  {
351  process[t].join();
352  }
353  }
354  else
355  {
356  unsigned int j = 0;
357  for (auto const& tri : mHullUnordered)
358  {
359  queryResult[j++] = mQuery.ToPlane(i, tri.V[0], tri.V[1], tri.V[2]);
360  }
361  }
362 
363  std::map<EdgeKey<false>, std::pair<int, int>> terminator;
364  std::vector<TriangleKey<true>> backFaces;
365  bool existsFrontFacingTriangle = false;
366  unsigned int j = 0;
367  for (auto const& tri : mHullUnordered)
368  {
369  if (queryResult[j++] <= 0)
370  {
371  // The triangle is back facing. These include triangles that
372  // are coplanar with the incoming point.
373  backFaces.push_back(tri);
374 
375  // The current hull is a 2-manifold watertight mesh. The
376  // terminator edges are those shared with a front-facing triangle.
377  // The first time an edge of a back-facing triangle is visited,
378  // insert it into the terminator. If it is visited a second time,
379  // the edge is removed because it is shared by another back-facing
380  // triangle. After all back-facing triangles are visited, the
381  // only remaining edges are shared by a single back-facing
382  // triangle, which makes them terminator edges.
383  for (int j0 = 2, j1 = 0; j1 < 3; j0 = j1++)
384  {
385  int v0 = tri.V[j0], v1 = tri.V[j1];
386  EdgeKey<false> edge(v0, v1);
387  auto iter = terminator.find(edge);
388  if (iter == terminator.end())
389  {
390  // The edge is visited for the first time.
391  terminator.insert(std::make_pair(edge, std::make_pair(v0, v1)));
392  }
393  else
394  {
395  // The edge is visited for the second time.
396  terminator.erase(edge);
397  }
398  }
399  }
400  else
401  {
402  // If there are no strictly front-facing triangles, then the
403  // incoming point is inside or on the convex hull. If we get
404  // to this code, then the point is truly outside and we can
405  // update the hull.
406  existsFrontFacingTriangle = true;
407  }
408  }
409 
410  if (!existsFrontFacingTriangle)
411  {
412  // The incoming point is inside or on the current hull, so no
413  // update of the hull is necessary.
414  return;
415  }
416 
417  // The updated hull contains the triangles not visible to the incoming
418  // point.
419  mHullUnordered = backFaces;
420 
421  // Insert the triangles formed by the incoming point and the terminator
422  // edges.
423  for (auto const& edge : terminator)
424  {
425  mHullUnordered.push_back(TriangleKey<true>(i, edge.second.second, edge.second.first));
426  }
427 }
428 
429 
430 }
bool operator()(int numPoints, Vector3< InputType > const *points, InputType epsilon)
Line3< InputType > const & GetLine() const
ConvexHull3(unsigned int numThreads=1)
unsigned int mNumThreads
void Update(int i)
std::vector< TriangleKey< true > > const & GetHullUnordered() const
int ToPlane(int i, int v0, int v1, int v2) const
ETManifoldMesh mHullMesh
int GetNumUniquePoints() const
std::vector< Vector3< ComputeType > > mComputePoints
PrimalQuery3< ComputeType > const & GetQuery() const
InputType mEpsilon
GLfloat GLfloat v1
Definition: glcorearb.h:812
std::vector< TriangleKey< true > > mHullUnordered
Vector< N, Real > UnitCross(Vector< N, Real > const &v0, Vector< N, Real > const &v1, bool robust=false)
Definition: GteVector3.h:130
PrimalQuery3< ComputeType > mQuery
GLfixed GLfixed GLint GLint GLfixed points
Definition: glext.h:4927
Plane3< InputType > mPlane
static Vector Zero()
Definition: GteVector.h:295
int GetDimension() const
virtual std::shared_ptr< Triangle > Insert(int v0, int v1, int v2)
Vector3< Real > direction[3]
Definition: GteVector3.h:96
GLfloat v0
Definition: glcorearb.h:811
GLdouble GLdouble t
Definition: glext.h:239
InputType GetEpsilon() const
int GetNumPoints() const
ETManifoldMesh const & GetHullMesh() const
void Set(int numVertices, Vector3< Real > const *vertices)
TMap const & GetTriangles() const
Vector3< Real > origin
Definition: GteVector3.h:95
Vector3< InputType > const * GetPoints() const
Line3< InputType > mLine
Plane3< InputType > const & GetPlane() const
Vector3< InputType > const * mPoints


geometric_tools_engine
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 03:59:59