GteMinimumVolumeBox3.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 
11 #include <Mathematics/GteEdgeKey.h>
14 #include <thread>
15 #include <type_traits>
16 
17 // Compute a minimum-volume oriented box containing the specified points. The
18 // algorithm is really about computing the minimum-volume box containing the
19 // convex hull of the points, so we must compute the convex hull or you must
20 // pass an already built hull to the code.
21 //
22 // The minimum-volume oriented box has a face coincident with a hull face
23 // or has three mutually orthogonal edges coincident with three hull edges
24 // that (of course) are mutually orthogonal.
25 // J.O'Rourke, "Finding minimal enclosing boxes",
26 // Internat. J. Comput. Inform. Sci., 14:183-199, 1985.
27 //
28 // A detailed description of the algorithm and implementation is found in
29 // the documents
30 // http://www.geometrictools.com/Documentation/MinimumVolumeBox.pdf
31 // http://www.geometrictools.com/Documentation/MinimumAreaRectangle.pdf
32 //
33 // NOTE: This algorithm guarantees a correct output only when ComputeType is
34 // an exact arithmetic type that supports division. In GTEngine, one such
35 // type is BSRational<UIntegerAP32> (arbitrary precision). Another such type
36 // is BSRational<UIntegerFP32<N>> (fixed precision), where N is chosen large
37 // enough for your input data sets. If you choose ComputeType to be 'float'
38 // or 'double', the output is not guaranteed to be correct.
39 //
40 // See GeometricTools/GTEngine/Samples/Geometrics/MinimumVolumeBox3 for an
41 // example of how to use the code.
42 
43 namespace gte
44 {
45 
46 template <typename InputType, typename ComputeType>
48 {
49 public:
50  // The class is a functor to support computing the minimum-volume box of
51  // multiple data sets using the same class object. For multithreading
52  // in ProcessFaces, choose 'numThreads' subject to the constraints
53  // 1 <= numThreads <= std::thread::hardware_concurrency()
54  // To execute ProcessEdges in a thread separate from the main thrad,
55  // choose 'threadProcessEdges' to 'true'.
56  MinimumVolumeBox3(unsigned int numThreads = 1, bool threadProcessEdges = false);
57 
58  // The points are arbitrary, so we must compute the convex hull from
59  // them in order to compute the minimum-area box. The input parameters
60  // are necessary for using ConvexHull3.
62  bool useRotatingCalipers = !std::is_floating_point<ComputeType>::value);
63 
64  // The points form a nondegenerate convex polyhedron. The indices input
65  // must be nonnull and specify the triangle faces.
66  OrientedBox3<InputType> operator()(int numPoints, Vector3<InputType> const* points,
67  int numIndices, int const* indices,
68  bool useRotatingCalipers = !std::is_floating_point<ComputeType>::value);
69 
70  // Member access.
71  inline int GetNumPoints() const;
72  inline Vector3<InputType> const* GetPoints() const;
73  inline std::vector<int> const& GetHull() const;
74  inline InputType GetVolume() const;
75 
76 private:
77  struct Box
78  {
80  ComputeType sqrLenU[3], range[3][2], volume;
81  };
82 
84  {
86  std::array<int, 4> index;
87  ComputeType sqrLenU[2], area;
88  };
89 
90  // Compute the minimum-volume box relative to each hull face.
91  void ProcessFaces(ETManifoldMesh const& mesh, Box& minBox);
92 
93  // Compute the minimum-volume box for each triple of orthgonal hull edges.
94  void ProcessEdges(ETManifoldMesh const& mesh, Box& minBox);
95 
96  // Compute the minimum-volume box relative to a single hull face.
98  void ProcessFace(std::shared_ptr<Triangle> const& supportTri,
99  std::vector<Vector3<ComputeType>> const& normal,
100  std::map<std::shared_ptr<Triangle>, int> const& triNormalMap,
101  ETManifoldMesh::EMap const& emap, Box& localMinBox);
102 
103  // The rotating calipers algorithm has a loop invariant that requires
104  // the convex polygon not to have collinear points. Any such points
105  // must be removed first. The code is also executed for the O(n^2)
106  // algorithm to reduce the number of process edges.
107  void RemoveCollinearPoints(Vector3<ComputeType> const& N, std::vector<int>& polyline);
108 
109  // This is the slow order O(n^2) search.
110  void ComputeBoxForFaceOrderNSqr(Vector3<ComputeType> const& N, std::vector<int> const& polyline, Box& box);
111 
112  // This is the rotating calipers version, which is O(n).
113  void ComputeBoxForFaceOrderN(Vector3<ComputeType> const& N, std::vector<int> const& polyline, Box& box);
114 
115  // Compute the smallest rectangle for the polyline edge <V[i0],V[i1]>.
116  ExtrudeRectangle SmallestRectangle(int i0, int i1, Vector3<ComputeType> const& N, std::vector<int> const& polyline);
117 
118  // Compute (sin(angle))^2 for the polyline edges emanating from the
119  // support vertices of the rectangle. The return value is 'true' if at
120  // least one angle is in [0,pi/2); otherwise, the return value is 'false'
121  // and the original polyline must project to a rectangle.
122  bool ComputeAngles(Vector3<ComputeType> const& N,
123  std::vector<int> const& polyline, ExtrudeRectangle const& rct,
124  std::array<std::pair<ComputeType, int>, 4>& A, int& numA) const;
125 
126  // Sort the angles indirectly. The sorted indices are returned. This
127  // avoids swapping elements of A[], which can be expensive when
128  // ComputeType is an exact rational type.
129  std::array<int, 4> SortAngles(std::array<std::pair<ComputeType, int>, 4> const& A, int numA) const;
130 
131  bool UpdateSupport(std::array<std::pair<ComputeType, int>, 4> const& A, int numA,
132  std::array<int, 4> const& sort, Vector3<ComputeType> const& N, std::vector<int> const& polyline,
133  std::vector<bool>& visited, ExtrudeRectangle& rct);
134 
135  // Convert the extruded box to the minimum-volume box of InputType. When
136  // the ComputeType is an exact rational type, the conversions are
137  // performed to avoid precision loss until necessary at the last step.
138  void ConvertTo(Box const& minBox, OrientedBox3<InputType>& itMinBox);
139 
140  // The code is multithreaded, both for convex hull computation and
141  // computing minimum-volume extruded boxes for the hull faces. The
142  // default value is 1, which implies a single-threaded computation (on
143  // the main thread).
144  unsigned int mNumThreads;
146 
147  // The input points to be bound.
150 
151  // The ComputeType conversions of the input points. Only points of the
152  // convex hull (vertices of a convex polyhedron) are converted for
153  // performance when ComputeType is rational.
155 
156  // The indices into mPoints/mComputePoints for the convex hull vertices.
157  std::vector<int> mHull;
158 
159  // The unique indices in mHull. This set allows us to compute only for
160  // the hull vertices and avoids redundant computations if the indices
161  // were to have repeated indices into mPoints/mComputePoints. This is
162  // a performance improvement for rational ComputeType.
163  std::set<int> mUniqueIndices;
164 
165  // The caller can specify whether to use rotating calipers or the slower
166  // all-edge processing for computing an extruded bounding box.
168 
169  // The volume of the minimum-volume box. The ComputeType value is exact,
170  // so the only rounding errors occur in the conversion from ComputeType
171  // to InputType (default rounding mode is round-to-nearest-ties-to-even).
172  InputType mVolume;
173 
174  // Convenient values that occur regularly in the code. When using
175  // rational ComputeType, we construct these numbers only once.
176  ComputeType mZero, mOne, mNegOne, mHalf;
177 };
178 
179 
180 template <typename InputType, typename ComputeType>
181 MinimumVolumeBox3<InputType, ComputeType>::MinimumVolumeBox3(unsigned int numThreads, bool threadProcessEdges)
182  :
183  mNumThreads(numThreads),
184  mThreadProcessEdges(threadProcessEdges),
185  mNumPoints(0),
186  mPoints(nullptr),
187  mComputePoints(nullptr),
188  mUseRotatingCalipers(true),
189  mVolume((InputType)0),
190  mZero(0),
191  mOne(1),
192  mNegOne(-1),
193  mHalf((InputType)0.5)
194 {
195 }
196 
197 template <typename InputType, typename ComputeType>
199  int numPoints, Vector3<InputType> const* points, bool useRotatingCalipers)
200 {
201  mNumPoints = numPoints;
202  mPoints = points;
203  mUseRotatingCalipers = useRotatingCalipers;
204  mHull.clear();
205  mUniqueIndices.clear();
206 
207  // Get the convex hull of the points.
209  ch3(mNumPoints, mPoints, (InputType)0);
210  int dimension = ch3.GetDimension();
211 
212  OrientedBox3<InputType> itMinBox;
213 
214  if (dimension == 0)
215  {
216  // The points are all effectively the same (using fuzzy epsilon).
217  itMinBox.center = mPoints[0];
218  itMinBox.axis[0] = Vector3<InputType>::Unit(0);
219  itMinBox.axis[1] = Vector3<InputType>::Unit(1);
220  itMinBox.axis[2] = Vector3<InputType>::Unit(2);
221  itMinBox.extent[0] = (InputType)0;
222  itMinBox.extent[1] = (InputType)0;
223  itMinBox.extent[2] = (InputType)0;
224  mHull.resize(1);
225  mHull[0] = 0;
226  return itMinBox;
227  }
228 
229  if (dimension == 1)
230  {
231  // The points effectively lie on a line (using fuzzy epsilon).
232  // Determine the extreme t-values for the points represented as
233  // P = origin + t*direction. We know that 'origin' is an input
234  // vertex, so we can start both t-extremes at zero.
235  Line3<InputType> const& line = ch3.GetLine();
236  InputType tmin = (InputType)0, tmax = (InputType)0;
237  int imin = 0, imax = 0;
238  for (int i = 0; i < mNumPoints; ++i)
239  {
240  Vector3<InputType> diff = mPoints[i] - line.origin;
241  InputType t = Dot(diff, line.direction);
242  if (t > tmax)
243  {
244  tmax = t;
245  imax = i;
246  }
247  else if (t < tmin)
248  {
249  tmin = t;
250  imin = i;
251  }
252  }
253 
254  itMinBox.center = line.origin + ((InputType)0.5)*(tmin + tmax) * line.direction;
255  itMinBox.extent[0] = ((InputType)0.5)*(tmax - tmin);
256  itMinBox.extent[1] = (InputType)0;
257  itMinBox.extent[2] = (InputType)0;
258  itMinBox.axis[0] = line.direction;
259  ComputeOrthogonalComplement(1, &itMinBox.axis[0]);
260  mHull.resize(2);
261  mHull[0] = imin;
262  mHull[1] = imax;
263  return itMinBox;
264  }
265 
266  if (dimension == 2)
267  {
268  // The points effectively line on a plane (using fuzzy epsilon).
269  // Project the points onto the plane and compute the minimum-area
270  // bounding box of them.
271  Plane3<InputType> const& plane = ch3.GetPlane();
272 
273  // Get a coordinate system relative to the plane of the points.
274  // Choose the origin to be any of the input points.
275  Vector3<InputType> origin = mPoints[0];
276  Vector3<InputType> basis[3];
277  basis[0] = plane.normal;
278  ComputeOrthogonalComplement(1, basis);
279 
280  // Project the input points onto the plane.
281  std::vector<Vector2<InputType>> projection(mNumPoints);
282  for (int i = 0; i < mNumPoints; ++i)
283  {
284  Vector3<InputType> diff = mPoints[i] - origin;
285  projection[i][0] = Dot(basis[1], diff);
286  projection[i][1] = Dot(basis[2], diff);
287  }
288 
289  // Compute the minimum area box in 2D.
291  OrientedBox2<InputType> rectangle = mab2(mNumPoints, &projection[0]);
292 
293  // Lift the values into 3D.
294  itMinBox.center = origin + rectangle.center[0] * basis[1] + rectangle.center[1] * basis[2];
295  itMinBox.axis[0] = rectangle.axis[0][0] * basis[1] + rectangle.axis[0][1] * basis[2];
296  itMinBox.axis[1] = rectangle.axis[1][0] * basis[1] + rectangle.axis[1][1] * basis[2];
297  itMinBox.axis[2] = basis[0];
298  itMinBox.extent[0] = rectangle.extent[0];
299  itMinBox.extent[1] = rectangle.extent[1];
300  itMinBox.extent[2] = (InputType)0;
301  mHull = mab2.GetHull();
302  return itMinBox;
303  }
304 
305  // Get the set of unique indices of the hull. This is used to project
306  // hull vertices onto lines.
307  ETManifoldMesh const& mesh = ch3.GetHullMesh();
308  mHull.resize(3 * mesh.GetTriangles().size());
309  int h = 0;
310  for (auto const& element : mesh.GetTriangles())
311  {
312  for (int i = 0; i < 3; ++i, ++h)
313  {
314  int index = element.first.V[i];
315  mHull[h] = index;
316  mUniqueIndices.insert(index);
317  }
318  }
319 
321 
322  Box minBox, minBoxEdges;
323  minBox.volume = mNegOne;
324  minBoxEdges.volume = mNegOne;
325 
327  {
328  std::thread doEdges([this, &mesh, &minBoxEdges]()
329  {
330  ProcessEdges(mesh, minBoxEdges);
331  });
332  ProcessFaces(mesh, minBox);
333  doEdges.join();
334  }
335  else
336  {
337  ProcessEdges(mesh, minBoxEdges);
338  ProcessFaces(mesh, minBox);
339  }
340 
341  if (minBoxEdges.volume != mNegOne
342  && minBoxEdges.volume < minBox.volume)
343  {
344  minBox = minBoxEdges;
345  }
346 
347  ConvertTo(minBox, itMinBox);
348  mComputePoints = nullptr;
349  return itMinBox;
350 }
351 
352 template <typename InputType, typename ComputeType>
354  int numPoints, Vector3<InputType> const* points, int numIndices,
355  int const* indices, bool useRotatingCalipers)
356 {
357  mNumPoints = numPoints;
358  mPoints = points;
359  mUseRotatingCalipers = useRotatingCalipers;
360  mUniqueIndices.clear();
361 
362  // Build the mesh from the indices. The box construction uses the edge
363  // map of the mesh.
364  ETManifoldMesh mesh;
365  int numTriangles = numIndices / 3;
366  for (int t = 0; t < numTriangles; ++t)
367  {
368  int v0 = *indices++;
369  int v1 = *indices++;
370  int v2 = *indices++;
371  mesh.Insert(v0, v1, v2);
372  }
373 
374  // Get the set of unique indices of the hull. This is used to project
375  // hull vertices onto lines.
376  mHull.resize(3 * mesh.GetTriangles().size());
377  int h = 0;
378  for (auto const& element : mesh.GetTriangles())
379  {
380  for (int i = 0; i < 3; ++i, ++h)
381  {
382  int index = element.first.V[i];
383  mHull[h] = index;
384  mUniqueIndices.insert(index);
385  }
386  }
387 
388  // Create the ComputeType points to be used downstream.
389  std::vector<Vector3<ComputeType>> computePoints(mNumPoints);
390  for (auto i : mUniqueIndices)
391  {
392  for (int j = 0; j < 3; ++j)
393  {
394  computePoints[i][j] = (ComputeType)mPoints[i][j];
395  }
396  }
397 
398  OrientedBox3<InputType> itMinBox;
399  mComputePoints = &computePoints[0];
400 
401  Box minBox, minBoxEdges;
402  minBox.volume = mNegOne;
403  minBoxEdges.volume = mNegOne;
404 
406  {
407  std::thread doEdges([this, &mesh, &minBoxEdges]()
408  {
409  ProcessEdges(mesh, minBoxEdges);
410  });
411  ProcessFaces(mesh, minBox);
412  doEdges.join();
413  }
414  else
415  {
416  ProcessEdges(mesh, minBoxEdges);
417  ProcessFaces(mesh, minBox);
418  }
419 
420  if (minBoxEdges.volume != mNegOne && minBoxEdges.volume < minBox.volume)
421  {
422  minBox = minBoxEdges;
423  }
424 
425  ConvertTo(minBox, itMinBox);
426  mComputePoints = nullptr;
427  return itMinBox;
428 }
429 
430 template <typename InputType, typename ComputeType> inline
432 {
433  return mNumPoints;
434 }
435 
436 template <typename InputType, typename ComputeType> inline
437 Vector3<InputType> const*
439 {
440  return mPoints;
441 }
442 
443 template <typename InputType, typename ComputeType> inline
445  const
446 {
447  return mHull;
448 }
449 
450 template <typename InputType, typename ComputeType> inline
452 {
453  return mVolume;
454 }
455 
456 template <typename InputType, typename ComputeType>
458 {
459  // Get the mesh data structures.
460  auto const& tmap = mesh.GetTriangles();
461  auto const& emap = mesh.GetEdges();
462 
463  // Compute inner-pointing face normals for searching boxes supported by
464  // a face and an extreme vertex. The indirection in triNormalMap, using
465  // an integer index instead of the normal/sqrlength pair itself, avoids
466  // expensive copies when using exact arithmetic.
467  std::vector<Vector3<ComputeType>> normal(tmap.size());
468  std::map<std::shared_ptr<Triangle>, int> triNormalMap;
469  int index = 0;
470  for (auto const& element : tmap)
471  {
472  auto tri = element.second;
473  Vector3<ComputeType> const& v0 = mComputePoints[tri->V[0]];
474  Vector3<ComputeType> const& v1 = mComputePoints[tri->V[1]];
475  Vector3<ComputeType> const& v2 = mComputePoints[tri->V[2]];
476  Vector3<ComputeType> edge1 = v1 - v0;
477  Vector3<ComputeType> edge2 = v2 - v0;
478  normal[index] = Cross(edge2, edge1); // inner-pointing normal
479  triNormalMap[tri] = index++;
480  }
481 
482  // Process the triangle faces. For each face, compute the polyline of
483  // edges that supports the bounding box with a face coincident to the
484  // triangle face. The projection of the polyline onto the plane of the
485  // triangle face is a convex polygon, so we can use the method of rotating
486  // calipers to compute its minimum-area box efficiently.
487  unsigned int numFaces = static_cast<unsigned int>(tmap.size());
488  if (mNumThreads > 1 && numFaces >= mNumThreads)
489  {
490  // Repackage the triangle pointers to support the partitioning of
491  // faces for multithreaded face processing.
492  std::vector<std::shared_ptr<Triangle>> triangles;
493  triangles.reserve(numFaces);
494  for (auto const& element : tmap)
495  {
496  triangles.push_back(element.second);
497  }
498 
499  // Partition the data for multiple threads.
500  unsigned int numFacesPerThread = numFaces / mNumThreads;
501  std::vector<unsigned int> imin(mNumThreads), imax(mNumThreads);
502  std::vector<Box> localMinBox(mNumThreads);
503  for (unsigned int t = 0; t < mNumThreads; ++t)
504  {
505  imin[t] = t * numFacesPerThread;
506  imax[t] = imin[t] + numFacesPerThread - 1;
507  localMinBox[t].volume = mNegOne;
508  }
509  imax[mNumThreads - 1] = numFaces - 1;
510 
511  // Execute the face processing in multiple threads.
512  std::vector<std::thread> process(mNumThreads);
513  for (unsigned int t = 0; t < mNumThreads; ++t)
514  {
515  process[t] = std::thread([this, t, &imin, &imax, &triangles,
516  &normal, &triNormalMap, &emap, &localMinBox]()
517  {
518  for (unsigned int i = imin[t]; i <= imax[t]; ++i)
519  {
520  auto const& supportTri = triangles[i];
521  ProcessFace(supportTri, normal, triNormalMap, emap, localMinBox[t]);
522  }
523  });
524  }
525 
526  // Wait for all threads to finish.
527  for (unsigned int t = 0; t < mNumThreads; ++t)
528  {
529  process[t].join();
530 
531  // Update the minimum-volume box candidate.
532  if (minBox.volume == mNegOne || localMinBox[t].volume < minBox.volume)
533  {
534  minBox = localMinBox[t];
535  }
536  }
537  }
538  else
539  {
540  for (auto const& element : tmap)
541  {
542  auto const& supportTri = element.second;
543  ProcessFace(supportTri, normal, triNormalMap, emap, minBox);
544  }
545  }
546 }
547 
548 template <typename InputType, typename ComputeType>
550 {
551  // The minimum-volume box can also be supported by three mutually
552  // orthogonal edges of the convex hull. For each triple of orthogonal
553  // edges, compute the minimum-volume box for that coordinate frame by
554  // projecting the points onto the axes of the frame. Use a hull vertex
555  // as the origin.
556  int index = mesh.GetTriangles().begin()->first.V[0];
557  Vector3<ComputeType> const& origin = mComputePoints[index];
559  std::array<ComputeType, 3> sqrLenU;
560 
561  auto const& emap = mesh.GetEdges();
562  auto e2 = emap.begin(), end = emap.end();
563  for (; e2 != end; ++e2)
564  {
565  U[2] = mComputePoints[e2->first.V[1]] - mComputePoints[e2->first.V[0]];
566  auto e1 = e2;
567  for (++e1; e1 != end; ++e1)
568  {
569  U[1] = mComputePoints[e1->first.V[1]] - mComputePoints[e1->first.V[0]];
570  if (Dot(U[1], U[2]) != mZero)
571  {
572  continue;
573  }
574  sqrLenU[1] = Dot(U[1], U[1]);
575 
576  auto e0 = e1;
577  for (++e0; e0 != end; ++e0)
578  {
579  U[0] = mComputePoints[e0->first.V[1]] - mComputePoints[e0->first.V[0]];
580  sqrLenU[0] = Dot(U[0], U[0]);
581  if (Dot(U[0], U[1]) != mZero || Dot(U[0], U[2]) != mZero)
582  {
583  continue;
584  }
585 
586  // The three edges are mutually orthogonal. To support exact
587  // rational arithmetic for volume computation, we replace U[2]
588  // by a parallel vector.
589  U[2] = Cross(U[0], U[1]);
590  sqrLenU[2] = sqrLenU[0] * sqrLenU[1];
591 
592  // Project the vertices onto the lines containing the edges.
593  // Use vertex 0 as the origin.
594  std::array<ComputeType, 3> umin, umax;
595  for (int j = 0; j < 3; ++j)
596  {
597  umin[j] = mZero;
598  umax[j] = mZero;
599  }
600 
601  for (auto i : mUniqueIndices)
602  {
603  Vector3<ComputeType> diff = mComputePoints[i] - origin;
604  for (int j = 0; j < 3; ++j)
605  {
606  ComputeType dot = Dot(diff, U[j]);
607  if (dot < umin[j])
608  {
609  umin[j] = dot;
610  }
611  else if (dot > umax[j])
612  {
613  umax[j] = dot;
614  }
615  }
616  }
617 
618  ComputeType volume = (umax[0] - umin[0]) / sqrLenU[0];
619  volume *= (umax[1] - umin[1]) / sqrLenU[1];
620  volume *= (umax[2] - umin[2]);
621 
622  // Update current minimum-volume box (if necessary).
623  if (minBox.volume == mOne || volume < minBox.volume)
624  {
625  // The edge keys have unordered vertices, so it is
626  // possible that {U[0],U[1],U[2]} is a left-handed set.
627  // We need a right-handed set.
628  if (DotCross(U[0], U[1], U[2]) < mZero)
629  {
630  U[2] = -U[2];
631  }
632 
633  minBox.P = origin;
634  for (int j = 0; j < 3; ++j)
635  {
636  minBox.U[j] = U[j];
637  minBox.sqrLenU[j] = sqrLenU[j];
638  for (int k = 0; k < 3; ++k)
639  {
640  minBox.range[k][0] = umin[k];
641  minBox.range[k][1] = umax[k];
642  }
643  }
644  minBox.volume = volume;
645 
646  }
647  }
648  }
649  }
650 }
651 
652 template <typename InputType, typename ComputeType>
653 void MinimumVolumeBox3<InputType, ComputeType>::ProcessFace(std::shared_ptr<Triangle> const& supportTri,
654  std::vector<Vector3<ComputeType>> const& normal, std::map<std::shared_ptr<Triangle>, int> const& triNormalMap,
655  ETManifoldMesh::EMap const& emap, Box& localMinBox)
656 {
657  // Get the supporting triangle information.
658  Vector3<ComputeType> const& supportNormal = normal[triNormalMap.find(supportTri)->second];
659 
660  // Build the polyline of supporting edges. The pair (v,polyline[v])
661  // represents an edge directed appropriately (see next set of
662  // comments).
663  std::vector<int> polyline(mNumPoints);
664  int polylineStart = -1;
665  for (auto const& edgeElement : emap)
666  {
667  auto const& edge = *edgeElement.second;
668  auto const& tri0 = edge.T[0].lock();
669  auto const& tri1 = edge.T[1].lock();
670  auto const& normal0 = normal[triNormalMap.find(tri0)->second];
671  auto const& normal1 = normal[triNormalMap.find(tri1)->second];
672  ComputeType dot0 = Dot(supportNormal, normal0);
673  ComputeType dot1 = Dot(supportNormal, normal1);
674 
675  std::shared_ptr<Triangle> tri;
676  if (dot0 < mZero && dot1 >= mZero)
677  {
678  tri = tri0;
679  }
680  else if (dot1 < mZero && dot0 >= mZero)
681  {
682  tri = tri1;
683  }
684 
685  if (tri)
686  {
687  // The edge supports the bounding box. Insert the edge in the
688  // list using clockwise order relative to tri. This will lead
689  // to a polyline whose projection onto the plane of the hull
690  // face is a convex polygon that is counterclockwise oriented.
691  for (int j0 = 2, j1 = 0; j1 < 3; j0 = j1++)
692  {
693  if (tri->V[j1] == edge.V[0])
694  {
695  if (tri->V[j0] == edge.V[1])
696  {
697  polyline[edge.V[1]] = edge.V[0];
698  }
699  else
700  {
701  polyline[edge.V[0]] = edge.V[1];
702  }
703  polylineStart = edge.V[0];
704  break;
705  }
706  }
707  }
708  }
709 
710  // Rearrange the edges to form a closed polyline. For M vertices, each
711  // ComputeBoxFor*() function starts with the edge from closedPolyline[M-1]
712  // to closedPolyline[0].
713  std::vector<int> closedPolyline(mNumPoints);
714  int numClosedPolyline = 0;
715  int v = polylineStart;
716  for (auto& cp : closedPolyline)
717  {
718  cp = v;
719  ++numClosedPolyline;
720  v = polyline[v];
721  if (v == polylineStart)
722  {
723  break;
724  }
725  }
726  closedPolyline.resize(numClosedPolyline);
727 
728  // This avoids redundant face testing in the O(n^2) or O(n) algorithms
729  // and it simplifies the O(n) implementation.
730  RemoveCollinearPoints(supportNormal, closedPolyline);
731 
732  // Compute the box coincident to the hull triangle that has minimum
733  // area on the face coincident with the triangle.
734  Box faceBox;
736  {
737  ComputeBoxForFaceOrderN(supportNormal, closedPolyline, faceBox);
738  }
739  else
740  {
741  ComputeBoxForFaceOrderNSqr(supportNormal, closedPolyline, faceBox);
742  }
743 
744  // Update the minimum-volume box candidate.
745  if (localMinBox.volume == mNegOne || faceBox.volume < localMinBox.volume)
746  {
747  localMinBox = faceBox;
748  }
749 }
750 
751 template <typename InputType, typename ComputeType>
753  Vector3<ComputeType> const& N, std::vector<int>& polyline)
754 {
755  std::vector<int> tmpPolyline = polyline;
756 
757  int const numPolyline = static_cast<int>(polyline.size());
758  int numNoncollinear = 0;
759  Vector3<ComputeType> ePrev =
760  mComputePoints[tmpPolyline[0]] - mComputePoints[tmpPolyline.back()];
761 
762  for (int i0 = 0, i1 = 1; i0 < numPolyline; ++i0)
763  {
764  Vector3<ComputeType> eNext =
765  mComputePoints[tmpPolyline[i1]] - mComputePoints[tmpPolyline[i0]];
766 
767  ComputeType tsp = DotCross(ePrev, eNext, N);
768  if (tsp != mZero)
769  {
770  polyline[numNoncollinear++] = tmpPolyline[i0];
771  }
772 
773  ePrev = eNext;
774  if (++i1 == numPolyline)
775  {
776  i1 = 0;
777  }
778  }
779 
780  polyline.resize(numNoncollinear);
781 }
782 
783 template <typename InputType, typename ComputeType>
785  Vector3<ComputeType> const& N, std::vector<int> const& polyline,
786  Box& box)
787 {
788  // This code processes the polyline terminator associated with a convex
789  // hull face of inner-pointing normal N. The polyline is usually not
790  // contained by a plane, and projecting the polyline to a convex polygon
791  // in a plane perpendicular to N introduces floating-point rounding
792  // errors. The minimum-area box for the projected polyline is computed
793  // indirectly to support exact rational arithmetic.
794 
795  box.P = mComputePoints[polyline[0]];
796  box.U[2] = N;
797  box.sqrLenU[2] = Dot(N, N);
798  box.range[1][0] = mZero;
799  box.volume = mNegOne;
800  int const numPolyline = static_cast<int>(polyline.size());
801  for (int i0 = numPolyline - 1, i1 = 0; i1 < numPolyline; i0 = i1++)
802  {
803  // Create a coordinate system for the plane perpendicular to the face
804  // normal and containing a polyline vertex.
805  Vector3<ComputeType> const& P = mComputePoints[polyline[i0]];
807  mComputePoints[polyline[i1]] - mComputePoints[polyline[i0]];
808 
809  Vector3<ComputeType> U1 = Cross(N, E);
810  Vector3<ComputeType> U0 = Cross(U1, N);
811 
812  // Compute the smallest rectangle containing the projected polyline.
813  ComputeType min0 = mZero, max0 = mZero, max1 = mZero;
814  for (int j = 0; j < numPolyline; ++j)
815  {
816  Vector3<ComputeType> diff = mComputePoints[polyline[j]] - P;
817  ComputeType dot = Dot(U0, diff);
818  if (dot < min0)
819  {
820  min0 = dot;
821  }
822  else if (dot > max0)
823  {
824  max0 = dot;
825  }
826 
827  dot = Dot(U1, diff);
828  if (dot > max1)
829  {
830  max1 = dot;
831  }
832  }
833 
834  // The true area is Area(rectangle)*Length(N). After the smallest
835  // scaled-area rectangle is computed and returned, the box.volume is
836  // updated to be the actual squared volume of the box.
837  ComputeType sqrLenU1 = Dot(U1, U1);
838  ComputeType volume = (max0 - min0) * max1 / sqrLenU1;
839  if (box.volume == mNegOne || volume < box.volume)
840  {
841  box.P = P;
842  box.U[0] = U0;
843  box.U[1] = U1;
844  box.sqrLenU[0] = sqrLenU1 * box.sqrLenU[2];
845  box.sqrLenU[1] = sqrLenU1;
846  box.range[0][0] = min0;
847  box.range[0][1] = max0;
848  box.range[1][1] = max1;
849  box.volume = volume;
850  }
851  }
852 
853  // Compute the range of points in the support-normal direction.
854  box.range[2][0] = mZero;
855  box.range[2][1] = mZero;
856  for (auto i : mUniqueIndices)
857  {
858  Vector3<ComputeType> diff = mComputePoints[i] - box.P;
859  ComputeType height = Dot(box.U[2], diff);
860  if (height < box.range[2][0])
861  {
862  box.range[2][0] = height;
863  }
864  else if (height > box.range[2][1])
865  {
866  box.range[2][1] = height;
867  }
868  }
869 
870  // Compute the actual volume.
871  box.volume *= (box.range[2][1] - box.range[2][0]) / box.sqrLenU[2];
872 }
873 
874 template <typename InputType, typename ComputeType>
876  Vector3<ComputeType> const& N, std::vector<int> const& polyline, Box& box)
877 {
878  // This code processes the polyline terminator associated with a convex
879  // hull face of inner-pointing normal N. The polyline is usually not
880  // contained by a plane, and projecting the polyline to a convex polygon
881  // in a plane perpendicular to N introduces floating-point rounding
882  // errors. The minimum-area box for the projected polyline is computed
883  // indirectly to support exact rational arithmetic.
884 
885  // When the bounding box corresponding to a polyline edge is computed,
886  // we mark the edge as visited. If the edge is encountered later, the
887  // algorithm terminates.
888  std::vector<bool> visited(polyline.size());
889  std::fill(visited.begin(), visited.end(), false);
890 
891  // Start the minimum-area rectangle search with the edge from the last
892  // polyline vertex to the first. When updating the extremes, we want the
893  // bottom-most point on the left edge, the top-most point on the right
894  // edge, the left-most point on the top edge, and the right-most point
895  // on the bottom edge. The polygon edges starting at these points are
896  // then guaranteed not to coincide with a box edge except when an extreme
897  // point is shared by two box edges (at a corner).
898  ExtrudeRectangle minRct = SmallestRectangle((int)polyline.size() - 1, 0,
899  N, polyline);
900  visited[minRct.index[0]] = true;
901 
902  // Execute the rotating calipers algorithm.
903  ExtrudeRectangle rct = minRct;
904  for (size_t i = 0; i < polyline.size(); ++i)
905  {
906  std::array<std::pair<ComputeType, int>, 4> A;
907  int numA;
908  if (!ComputeAngles(N, polyline, rct, A, numA))
909  {
910  // The polyline projects to a rectangle, so the search is over.
911  break;
912  }
913 
914  // Indirectly sort the A-array.
915  std::array<int, 4> sort = SortAngles(A, numA);
916 
917  // Update the supporting indices (rct.index[]) and the rectangle axis
918  // directions (rct.U[]).
919  if (!UpdateSupport(A, numA, sort, N, polyline, visited, rct))
920  {
921  // We have already processed the rectangle polygon edge, so the
922  // search is over.
923  break;
924  }
925 
926  if (rct.area < minRct.area)
927  {
928  minRct = rct;
929  }
930  }
931 
932  // Store relevant box information for computing volume and converting to
933  // an InputType bounding box.
934  box.P = mComputePoints[polyline[minRct.index[0]]];
935  box.U[0] = minRct.U[0];
936  box.U[1] = minRct.U[1];
937  box.U[2] = N;
938  box.sqrLenU[0] = minRct.sqrLenU[0];
939  box.sqrLenU[1] = minRct.sqrLenU[1];
940  box.sqrLenU[2] = Dot(box.U[2], box.U[2]);
941 
942  // Compute the range of points in the plane perpendicular to the support
943  // normal.
944  box.range[0][0] = Dot(box.U[0],
945  mComputePoints[polyline[minRct.index[3]]] - box.P);
946  box.range[0][1] = Dot(box.U[0],
947  mComputePoints[polyline[minRct.index[1]]] - box.P);
948  box.range[1][0] = mZero;
949  box.range[1][1] = Dot(box.U[1],
950  mComputePoints[polyline[minRct.index[2]]] - box.P);
951 
952  // Compute the range of points in the support-normal direction.
953  box.range[2][0] = mZero;
954  box.range[2][1] = mZero;
955  for (auto i : mUniqueIndices)
956  {
957  Vector3<ComputeType> diff = mComputePoints[i] - box.P;
958  ComputeType height = Dot(box.U[2], diff);
959  if (height < box.range[2][0])
960  {
961  box.range[2][0] = height;
962  }
963  else if (height > box.range[2][1])
964  {
965  box.range[2][1] = height;
966  }
967  }
968 
969  // Compute the actual volume.
970  box.volume =
971  (box.range[0][1] - box.range[0][0]) *
972  ((box.range[1][1] - box.range[1][0]) / box.sqrLenU[1]) *
973  ((box.range[2][1] - box.range[2][0]) / box.sqrLenU[2]);
974 }
975 
976 template <typename InputType, typename ComputeType>
979  Vector3<ComputeType> const& N, std::vector<int> const& polyline)
980 {
981  ExtrudeRectangle rct;
983  mComputePoints[polyline[i1]] - mComputePoints[polyline[i0]];
984  rct.U[1] = Cross(N, E);
985  rct.U[0] = Cross(rct.U[1], N);
986  rct.index = { i1, i1, i1, i1 };
987  rct.sqrLenU[0] = Dot(rct.U[0], rct.U[0]);
988  rct.sqrLenU[1] = Dot(rct.U[1], rct.U[1]);
989 
990  Vector3<ComputeType> const& origin = mComputePoints[polyline[i1]];
991  Vector2<ComputeType> support[4];
992  for (int j = 0; j < 4; ++j)
993  {
994  support[j] = { mZero, mZero };
995  }
996 
997  int i = 0;
998  for (auto p : polyline)
999  {
1000  Vector3<ComputeType> diff = mComputePoints[p] - origin;
1001  Vector2<ComputeType> v = { Dot(rct.U[0], diff), Dot(rct.U[1], diff) };
1002 
1003  // The right-most vertex of the bottom edge is vertices[i1]. The
1004  // assumption of no triple of collinear vertices guarantees that
1005  // box.index[0] is i1, which is the initial value assigned at the
1006  // beginning of this function. Therefore, there is no need to test
1007  // for other vertices farther to the right than vertices[i1].
1008 
1009  if (v[0] > support[1][0] ||
1010  (v[0] == support[1][0] && v[1] > support[1][1]))
1011  {
1012  // New right maximum OR same right maximum but closer to top.
1013  rct.index[1] = i;
1014  support[1] = v;
1015  }
1016 
1017  if (v[1] > support[2][1] ||
1018  (v[1] == support[2][1] && v[0] < support[2][0]))
1019  {
1020  // New top maximum OR same top maximum but closer to left.
1021  rct.index[2] = i;
1022  support[2] = v;
1023  }
1024 
1025  if (v[0] < support[3][0] ||
1026  (v[0] == support[3][0] && v[1] < support[3][1]))
1027  {
1028  // New left minimum OR same left minimum but closer to bottom.
1029  rct.index[3] = i;
1030  support[3] = v;
1031  }
1032 
1033  ++i;
1034  }
1035 
1036  // The comment in the loop has the implication that support[0] = { 0, 0 },
1037  // so the scaled height (support[2][1] - support[0][1]) is simply
1038  // support[2][1].
1039  ComputeType scaledWidth = support[1][0] - support[3][0];
1040  ComputeType scaledHeight = support[2][1];
1041  rct.area = scaledWidth * scaledHeight / rct.sqrLenU[1];
1042  return rct;
1043 }
1044 
1045 template <typename InputType, typename ComputeType>
1047  Vector3<ComputeType> const& N, std::vector<int> const& polyline,
1048  ExtrudeRectangle const& rct,
1049  std::array<std::pair<ComputeType, int>, 4>& A, int& numA) const
1050 {
1051  int const numPolyline = static_cast<int>(polyline.size());
1052  numA = 0;
1053  for (int k0 = 3, k1 = 0; k1 < 4; k0 = k1++)
1054  {
1055  if (rct.index[k0] != rct.index[k1])
1056  {
1057  // The rct edges are ordered in k1 as U[0], U[1], -U[0], -U[1].
1058  int lookup = (k0 & 1);
1060  ((k0 & 2) ? -rct.U[lookup] : rct.U[lookup]);
1061  int j0 = rct.index[k0], j1 = j0 + 1;
1062  if (j1 == numPolyline)
1063  {
1064  j1 = 0;
1065  }
1067  mComputePoints[polyline[j1]] - mComputePoints[polyline[j0]];
1068  Vector3<ComputeType> Eperp = Cross(N, E);
1069  E = Cross(Eperp, N);
1070  Vector3<ComputeType> DxE = Cross(D, E);
1071  ComputeType csqrlen = Dot(DxE, DxE);
1072  ComputeType dsqrlen = rct.sqrLenU[lookup];
1073  ComputeType esqrlen = Dot(E, E);
1074  ComputeType sinThetaSqr = csqrlen / (dsqrlen * esqrlen);
1075  A[numA++] = std::make_pair(sinThetaSqr, k0);
1076  }
1077  }
1078  return numA > 0;
1079 }
1080 
1081 template <typename InputType, typename ComputeType>
1083  std::array<std::pair<ComputeType, int>, 4> const& A, int numA) const
1084 {
1085  std::array<int, 4> sort = { 0, 1, 2, 3 };
1086  if (numA > 1)
1087  {
1088  if (numA == 2)
1089  {
1090  if (A[sort[0]].first > A[sort[1]].first)
1091  {
1092  std::swap(sort[0], sort[1]);
1093  }
1094  }
1095  else if (numA == 3)
1096  {
1097  if (A[sort[0]].first > A[sort[1]].first)
1098  {
1099  std::swap(sort[0], sort[1]);
1100  }
1101  if (A[sort[0]].first > A[sort[2]].first)
1102  {
1103  std::swap(sort[0], sort[2]);
1104  }
1105  if (A[sort[1]].first > A[sort[2]].first)
1106  {
1107  std::swap(sort[1], sort[2]);
1108  }
1109  }
1110  else // numA == 4
1111  {
1112  if (A[sort[0]].first > A[sort[1]].first)
1113  {
1114  std::swap(sort[0], sort[1]);
1115  }
1116  if (A[sort[2]].first > A[sort[3]].first)
1117  {
1118  std::swap(sort[2], sort[3]);
1119  }
1120  if (A[sort[0]].first > A[sort[2]].first)
1121  {
1122  std::swap(sort[0], sort[2]);
1123  }
1124  if (A[sort[1]].first > A[sort[3]].first)
1125  {
1126  std::swap(sort[1], sort[3]);
1127  }
1128  if (A[sort[1]].first > A[sort[2]].first)
1129  {
1130  std::swap(sort[1], sort[2]);
1131  }
1132  }
1133  }
1134  return sort;
1135 }
1136 
1137 template <typename InputType, typename ComputeType>
1139  std::array<std::pair<ComputeType, int>, 4> const& A, int numA,
1140  std::array<int, 4> const& sort, Vector3<ComputeType> const& N,
1141  std::vector<int> const& polyline, std::vector<bool>& visited,
1142  ExtrudeRectangle& rct)
1143 {
1144  // Replace the support vertices of those edges attaining minimum angle
1145  // with the other endpoints of the edges.
1146  int const numPolyline = static_cast<int>(polyline.size());
1147  auto const& amin = A[sort[0]];
1148  for (int k = 0; k < numA; ++k)
1149  {
1150  auto const& a = A[sort[k]];
1151  if (a.first == amin.first)
1152  {
1153  if (++rct.index[a.second] == numPolyline)
1154  {
1155  rct.index[a.second] = 0;
1156  }
1157  }
1158  else
1159  {
1160  break;
1161  }
1162  }
1163 
1164  int bottom = rct.index[amin.second];
1165  if (visited[bottom])
1166  {
1167  // We have already processed this polyline edge.
1168  return false;
1169  }
1170  visited[bottom] = true;
1171 
1172  // Cycle the vertices so that the bottom support occurs first.
1173  std::array<int, 4> nextIndex;
1174  for (int k = 0; k < 4; ++k)
1175  {
1176  nextIndex[k] = rct.index[(amin.second + k) % 4];
1177  }
1178  rct.index = nextIndex;
1179 
1180  // Compute the rectangle axis directions.
1181  int j1 = rct.index[0], j0 = j1 - 1;
1182  if (j1 < 0)
1183  {
1184  j1 = numPolyline - 1;
1185  }
1187  mComputePoints[polyline[j1]] - mComputePoints[polyline[j0]];
1188  rct.U[1] = Cross(N, E);
1189  rct.U[0] = Cross(rct.U[1], N);
1190  rct.sqrLenU[0] = Dot(rct.U[0], rct.U[0]);
1191  rct.sqrLenU[1] = Dot(rct.U[1], rct.U[1]);
1192 
1193  // Compute the rectangle area.
1194  Vector3<ComputeType> diff[2] =
1195  {
1196  mComputePoints[polyline[rct.index[1]]]
1197  - mComputePoints[polyline[rct.index[3]]],
1198  mComputePoints[polyline[rct.index[2]]]
1199  - mComputePoints[polyline[rct.index[0]]]
1200  };
1201  ComputeType scaledWidth = Dot(rct.U[0], diff[0]);
1202  ComputeType scaledHeight = Dot(rct.U[1], diff[1]);
1203  rct.area = scaledWidth * scaledHeight / rct.sqrLenU[1];
1204  return true;
1205 }
1206 
1207 template <typename InputType, typename ComputeType>
1209  OrientedBox3<InputType>& itMinBox)
1210 {
1211  Vector3<ComputeType> center = minBox.P;
1212  for (int i = 0; i < 3; ++i)
1213  {
1214  ComputeType average =
1215  mHalf * (minBox.range[i][0] + minBox.range[i][1]);
1216  center += (average / minBox.sqrLenU[i]) * minBox.U[i];
1217  }
1218 
1219  // Calculate the squared extent using ComputeType to avoid loss of
1220  // precision before computing a squared root.
1221  Vector3<ComputeType> sqrExtent;
1222  for (int i = 0; i < 3; ++i)
1223  {
1224  sqrExtent[i] = mHalf * (minBox.range[i][1] - minBox.range[i][0]);
1225  sqrExtent[i] *= sqrExtent[i];
1226  sqrExtent[i] /= minBox.sqrLenU[i];
1227  }
1228 
1229  for (int i = 0; i < 3; ++i)
1230  {
1231  itMinBox.center[i] = (InputType)center[i];
1232  itMinBox.extent[i] = sqrt((InputType)sqrExtent[i]);
1233 
1234  // Before converting to floating-point, factor out the maximum
1235  // component using ComputeType to generate rational numbers in a
1236  // range that avoids loss of precision during the conversion and
1237  // normalization.
1238  Vector3<ComputeType> const& axis = minBox.U[i];
1239  ComputeType cmax = std::max(std::abs(axis[0]), std::abs(axis[1]));
1240  cmax = std::max(cmax, std::abs(axis[2]));
1241  ComputeType invCMax = mOne / cmax;
1242  for (int j = 0; j < 3; ++j)
1243  {
1244  itMinBox.axis[i][j] = (InputType)(axis[j] * invCMax);
1245  }
1246  Normalize(itMinBox.axis[i]);
1247  }
1248 
1249  mVolume = (InputType)minBox.volume;
1250 }
1251 
1252 }
Vector3< InputType > const * mPoints
Line3< InputType > const & GetLine() const
void ProcessFaces(ETManifoldMesh const &mesh, Box &minBox)
std::array< Vector< N, Real >, N > axis
EMap const & GetEdges() const
void ComputeBoxForFaceOrderNSqr(Vector3< ComputeType > const &N, std::vector< int > const &polyline, Box &box)
gte::BSNumber< UIntegerType > abs(gte::BSNumber< UIntegerType > const &number)
Definition: GteBSNumber.h:966
OrientedBox3< InputType > operator()(int numPoints, Vector3< InputType > const *points, bool useRotatingCalipers=!std::is_floating_point< ComputeType >::value)
PrimalQuery3< ComputeType > const & GetQuery() const
Vector3< ComputeType > const * mComputePoints
void ConvertTo(Box const &minBox, OrientedBox3< InputType > &itMinBox)
void ProcessFace(std::shared_ptr< Triangle > const &supportTri, std::vector< Vector3< ComputeType >> const &normal, std::map< std::shared_ptr< Triangle >, int > const &triNormalMap, ETManifoldMesh::EMap const &emap, Box &localMinBox)
GLfloat GLfloat v1
Definition: glcorearb.h:812
GLsizei const GLfloat * value
Definition: glcorearb.h:819
InputType GetVolume() const
void RemoveCollinearPoints(Vector3< ComputeType > const &N, std::vector< int > &polyline)
std::vector< int > const & GetHull() const
ExtrudeRectangle SmallestRectangle(int i0, int i1, Vector3< ComputeType > const &N, std::vector< int > const &polyline)
Vector< N, Real > direction
Definition: GteLine.h:29
Vector< N, Real > extent
Vector3< Real > const * GetVertices() const
GLboolean GLboolean GLboolean GLboolean a
Definition: glcorearb.h:1217
std::vector< int > const & GetHull() const
void ProcessEdges(ETManifoldMesh const &mesh, Box &minBox)
GLfixed GLfixed GLint GLint GLfixed points
Definition: glext.h:4927
ETManifoldMesh::Triangle Triangle
GLuint GLuint end
Definition: glcorearb.h:470
GLsizei GLenum const void * indices
Definition: glcorearb.h:401
std::map< EdgeKey< false >, std::shared_ptr< Edge > > EMap
GLint first
Definition: glcorearb.h:400
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
int GetDimension() const
std::array< int, 4 > SortAngles(std::array< std::pair< ComputeType, int >, 4 > const &A, int numA) const
virtual std::shared_ptr< Triangle > Insert(int v0, int v1, int v2)
Real Normalize(GVector< Real > &v, bool robust=false)
Definition: GteGVector.h:454
GLfloat v0
Definition: glcorearb.h:811
GLdouble GLdouble t
Definition: glext.h:239
GLint GLsizei GLsizei height
Definition: glcorearb.h:98
bool UpdateSupport(std::array< std::pair< ComputeType, int >, 4 > const &A, int numA, std::array< int, 4 > const &sort, Vector3< ComputeType > const &N, std::vector< int > const &polyline, std::vector< bool > &visited, ExtrudeRectangle &rct)
DualQuaternion< Real > Cross(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
Real DotCross(Vector< N, Real > const &v0, Vector< N, Real > const &v1, Vector< N, Real > const &v2)
Definition: GteVector3.h:140
ETManifoldMesh const & GetHullMesh() const
GLfloat GLfloat GLfloat GLfloat h
Definition: glcorearb.h:1997
TMap const & GetTriangles() const
GLenum array
Definition: glext.h:6669
MinimumVolumeBox3(unsigned int numThreads=1, bool threadProcessEdges=false)
const GLdouble * v
Definition: glcorearb.h:832
GLfloat GLfloat GLfloat v2
Definition: glcorearb.h:813
GLuint index
Definition: glcorearb.h:781
Vector< N, Real > normal
Definition: GteHyperplane.h:40
Vector3< ComputeType > U[3]
GLenum GLint * range
Definition: glcorearb.h:1920
Vector< N, Real > origin
Definition: GteLine.h:29
Real ComputeOrthogonalComplement(int numInputs, Vector2< Real > *v, bool robust=false)
Definition: GteVector2.h:123
Vector3< InputType > const * GetPoints() const
void ComputeBoxForFaceOrderN(Vector3< ComputeType > const &N, std::vector< int > const &polyline, Box &box)
GLint GLint bottom
Definition: glcorearb.h:2000
GLfloat GLfloat p
Definition: glext.h:11668
Plane3< InputType > const & GetPlane() const
Vector< N, Real > center
static Vector Unit(int d)
Definition: GteVector.h:303
bool ComputeAngles(Vector3< ComputeType > const &N, std::vector< int > const &polyline, ExtrudeRectangle const &rct, std::array< std::pair< ComputeType, int >, 4 > &A, int &numA) const


geometric_tools_engine
Author(s): Yijiang Huang
autogenerated on Thu Jul 18 2019 04:00:01