GteMinimumAreaBox2.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.1 (2016/07/25)
7 
8 #pragma once
9 
12 #include <type_traits>
13 
14 // Compute a minimum-area oriented box containing the specified points. The
15 // algorithm uses the rotating calipers method.
16 // http://www-cgrl.cs.mcgill.ca/~godfried/research/calipers.html
17 // http://cgm.cs.mcgill.ca/~orm/rotcal.html
18 // The box is supported by the convex hull of the points, so the algorithm
19 // is really about computing the minimum-area box containing a convex polygon.
20 // The rotating calipers approach is O(n) in time for n polygon edges.
21 //
22 // A detailed description of the algorithm and implementation is found in
23 // http://www.geometrictools.com/Documentation/MinimumAreaRectangle.pdf
24 //
25 // NOTE: This algorithm guarantees a correct output only when ComputeType is
26 // an exact arithmetic type that supports division. In GTEngine, one such
27 // type is BSRational<UIntegerAP32> (arbitrary precision). Another such type
28 // is BSRational<UIntegerFP32<N>> (fixed precision), where N is chosen large
29 // enough for your input data sets. If you choose ComputeType to be 'float'
30 // or 'double', the output is not guaranteed to be correct.
31 //
32 // See GeometricTools/GTEngine/Samples/Geometrics/MinimumAreaBox2 for an
33 // example of how to use the code.
34 
35 namespace gte
36 {
37 
38 template <typename InputType, typename ComputeType>
40 {
41 public:
42  // The class is a functor to support computing the minimum-area box of
43  // multiple data sets using the same class object.
45 
46  // The points are arbitrary, so we must compute the convex hull from
47  // them in order to compute the minimum-area box. The input parameters
48  // are necessary for using ConvexHull2. NOTE: ConvexHull2 guarantees
49  // that the hull does not have three consecutive collinear points.
50  OrientedBox2<InputType> operator()(int numPoints,
52  bool useRotatingCalipers =
54 
55  // The points already form a counterclockwise, nondegenerate convex
56  // polygon. If the points directly are the convex polygon, set
57  // numIndices to 0 and indices to nullptr. If the polygon vertices
58  // are a subset of the incoming points, that subset is identified by
59  // numIndices >= 3 and indices having numIndices elements.
60  OrientedBox2<InputType> operator()(int numPoints,
61  Vector2<InputType> const* points, int numIndices, int const* indices,
62  bool useRotatingCalipers =
64 
65  // Member access.
66  inline int GetNumPoints() const;
67  inline Vector2<InputType> const* GetPoints() const;
68  inline std::vector<int> const& GetHull() const;
69  inline std::array<int, 4> const& GetSupportIndices() const;
70  inline InputType GetArea() const;
71 
72 private:
73  // The box axes are U[i] and are usually not unit-length in order to allow
74  // exact arithmetic. The box is supported by mPoints[index[i]], where i
75  // is one of the enumerations above. The box axes are not necessarily unit
76  // length, but they have the same length. They need to be normalized for
77  // conversion back to InputType.
78  struct Box
79  {
81  std::array<int, 4> index; // order: bottom, right, top, left
82  ComputeType sqrLenU0, area;
83  };
84 
85  // The rotating calipers algorithm has a loop invariant that requires
86  // the convex polygon not to have collinear points. Any such points
87  // must be removed first. The code is also executed for the O(n^2)
88  // algorithm to reduce the number of process edges.
89  void RemoveCollinearPoints(std::vector<Vector2<ComputeType>>& vertices);
90 
91  // This is the slow O(n^2) search.
93  std::vector<Vector2<ComputeType>> const& vertices);
94 
95  // The fast O(n) search.
97  std::vector<Vector2<ComputeType>> const& vertices);
98 
99  // Compute the smallest box for the polygon edge <V[i0],V[i1]>.
100  Box SmallestBox(int i0, int i1,
101  std::vector<Vector2<ComputeType>> const& vertices);
102 
103  // Compute (sin(angle))^2 for the polygon edges emanating from the support
104  // vertices of the box. The return value is 'true' if at least one angle
105  // is in [0,pi/2); otherwise, the return value is 'false' and the original
106  // polygon must be a rectangle.
107  bool ComputeAngles(std::vector<Vector2<ComputeType>> const& vertices,
108  Box const& box, std::array<std::pair<ComputeType, int>, 4>& A,
109  int& numA) const;
110 
111  // Sort the angles indirectly. The sorted indices are returned. This
112  // avoids swapping elements of A[], which can be expensive when
113  // ComputeType is an exact rational type.
114  std::array<int, 4> SortAngles(
115  std::array<std::pair<ComputeType, int>, 4> const& A, int numA) const;
116 
117  bool UpdateSupport(std::array<std::pair<ComputeType, int>, 4> const& A,
118  int numA, std::array<int, 4> const& sort,
119  std::vector<Vector2<ComputeType>> const& vertices,
120  std::vector<bool>& visited, Box& box);
121 
122  // Convert the ComputeType box to the InputType box. When the ComputeType
123  // is an exact rational type, the conversions are performed to avoid
124  // precision loss until necessary at the last step.
125  void ConvertTo(Box const& minBox,
126  std::vector<Vector2<ComputeType>> const& computePoints,
127  OrientedBox2<InputType>& itMinBox);
128 
129  // The input points to be bound.
132 
133  // The indices into mPoints/mComputePoints for the convex hull vertices.
134  std::vector<int> mHull;
135 
136  // The support indices for the minimum-area box.
137  std::array<int, 4> mSupportIndices;
138 
139  // The area of the minimum-area box. The ComputeType value is exact,
140  // so the only rounding errors occur in the conversion from ComputeType
141  // to InputType (default rounding mode is round-to-nearest-ties-to-even).
142  InputType mArea;
143 
144  // Convenient values that occur regularly in the code. When using
145  // rational ComputeType, we construct these numbers only once.
146  ComputeType mZero, mOne, mNegOne, mHalf;
147 };
148 
149 
150 template <typename InputType, typename ComputeType>
152  :
153  mNumPoints(0),
154  mPoints(nullptr),
155  mArea((InputType)0),
156  mZero(0),
157  mOne(1),
158  mNegOne(-1),
159  mHalf((InputType)0.5)
160 {
161  mSupportIndices = { 0, 0, 0, 0 };
162 }
163 
164 template <typename InputType, typename ComputeType>
166  int numPoints, Vector2<InputType> const* points, bool useRotatingCalipers)
167 {
168  mNumPoints = numPoints;
169  mPoints = points;
170  mHull.clear();
171 
172  // Get the convex hull of the points.
174  ch2(mNumPoints, mPoints, (InputType)0);
175  int dimension = ch2.GetDimension();
176 
178 
179  if (dimension == 0)
180  {
181  // The points are all effectively the same (using fuzzy epsilon).
182  minBox.center = mPoints[0];
183  minBox.axis[0] = Vector2<InputType>::Unit(0);
184  minBox.axis[1] = Vector2<InputType>::Unit(1);
185  minBox.extent[0] = (InputType)0;
186  minBox.extent[1] = (InputType)0;
187  mHull.resize(1);
188  mHull[0] = 0;
189  return minBox;
190  }
191 
192  if (dimension == 1)
193  {
194  // The points effectively lie on a line (using fuzzy epsilon).
195  // Determine the extreme t-values for the points represented as
196  // P = origin + t*direction. We know that 'origin' is an input
197  // vertex, so we can start both t-extremes at zero.
198  Line2<InputType> const& line = ch2.GetLine();
199  InputType tmin = (InputType)0, tmax = (InputType)0;
200  int imin = 0, imax = 0;
201  for (int i = 0; i < mNumPoints; ++i)
202  {
203  Vector2<InputType> diff = mPoints[i] - line.origin;
204  InputType t = Dot(diff, line.direction);
205  if (t > tmax)
206  {
207  tmax = t;
208  imax = i;
209  }
210  else if (t < tmin)
211  {
212  tmin = t;
213  imin = i;
214  }
215  }
216 
217  minBox.center = line.origin +
218  ((InputType)0.5)*(tmin + tmax) * line.direction;
219  minBox.extent[0] = ((InputType)0.5)*(tmax - tmin);
220  minBox.extent[1] = (InputType)0;
221  minBox.axis[0] = line.direction;
222  minBox.axis[1] = -Perp(line.direction);
223  mHull.resize(2);
224  mHull[0] = imin;
225  mHull[1] = imax;
226  return minBox;
227  }
228 
229  mHull = ch2.GetHull();
230  Vector2<ComputeType> const* queryPoints = ch2.GetQuery().GetVertices();
231  std::vector<Vector2<ComputeType>> computePoints(mHull.size());
232  for (size_t i = 0; i < mHull.size(); ++i)
233  {
234  computePoints[i] = queryPoints[mHull[i]];
235  }
236 
237  RemoveCollinearPoints(computePoints);
238 
239  Box box;
240  if (useRotatingCalipers)
241  {
242  box = ComputeBoxForEdgeOrderN(computePoints);
243  }
244  else
245  {
246  box = ComputeBoxForEdgeOrderNSqr(computePoints);
247  }
248 
249  ConvertTo(box, computePoints, minBox);
250  return minBox;
251 }
252 
253 template <typename InputType, typename ComputeType>
255  int numPoints, Vector2<InputType> const* points, int numIndices,
256  int const* indices, bool useRotatingCalipers)
257 {
258  mHull.clear();
259 
261 
262  if (numPoints < 3 || !points || (indices && numIndices < 3))
263  {
264  minBox.center = Vector2<InputType>::Zero();
265  minBox.axis[0] = Vector2<InputType>::Unit(0);
266  minBox.axis[1] = Vector2<InputType>::Unit(1);
267  minBox.extent = Vector2<InputType>::Zero();
268  return minBox;
269  }
270 
271  if (indices)
272  {
273  mHull.resize(numIndices);
274  std::copy(indices, indices + numIndices, mHull.begin());
275  }
276  else
277  {
278  numIndices = numPoints;
279  mHull.resize(numIndices);
280  for (int i = 0; i < numIndices; ++i)
281  {
282  mHull[i] = i;
283  }
284  }
285 
286  std::vector<Vector2<ComputeType>> computePoints(numIndices);
287  for (int i = 0; i < numIndices; ++i)
288  {
289  int h = mHull[i];
290  computePoints[i][0] = (ComputeType)points[h][0];
291  computePoints[i][1] = (ComputeType)points[h][1];
292  }
293 
294  RemoveCollinearPoints(computePoints);
295 
296  Box box;
297  if (useRotatingCalipers)
298  {
299  box = ComputeBoxForEdgeOrderN(computePoints);
300  }
301  else
302  {
303  box = ComputeBoxForEdgeOrderNSqr(computePoints);
304  }
305 
306  ConvertTo(box, computePoints, minBox);
307  return minBox;
308 }
309 
310 template <typename InputType, typename ComputeType> inline
312 {
313  return mNumPoints;
314 }
315 
316 template <typename InputType, typename ComputeType> inline
318  const
319 {
320  return mPoints;
321 }
322 
323 template <typename InputType, typename ComputeType> inline
324 std::vector<int> const&
326 {
327  return mHull;
328 }
329 
330 template <typename InputType, typename ComputeType> inline
331 std::array<int, 4> const&
333 {
334  return mSupportIndices;
335 }
336 
337 template <typename InputType, typename ComputeType> inline
339 {
340  return mArea;
341 }
342 
343 template <typename InputType, typename ComputeType>
345  std::vector<Vector2<ComputeType>>& vertices)
346 {
347  std::vector<Vector2<ComputeType>> tmpVertices = vertices;
348 
349  int const numVertices = static_cast<int>(vertices.size());
350  int numNoncollinear = 0;
351  Vector2<ComputeType> ePrev = tmpVertices[0] - tmpVertices.back();
352  for (int i0 = 0, i1 = 1; i0 < numVertices; ++i0)
353  {
354  Vector2<ComputeType> eNext = tmpVertices[i1] - tmpVertices[i0];
355 
356  ComputeType dp = DotPerp(ePrev, eNext);
357  if (dp != mZero)
358  {
359  vertices[numNoncollinear++] = tmpVertices[i0];
360  }
361 
362  ePrev = eNext;
363  if (++i1 == numVertices)
364  {
365  i1 = 0;
366  }
367  }
368 
369  vertices.resize(numNoncollinear);
370 }
371 
372 template <typename InputType, typename ComputeType>
375  std::vector<Vector2<ComputeType>> const& vertices)
376 {
377  Box minBox;
378  minBox.area = mNegOne;
379  int const numIndices = static_cast<int>(vertices.size());
380  for (int i0 = numIndices - 1, i1 = 0; i1 < numIndices; i0 = i1++)
381  {
382  Box box = SmallestBox(i0, i1, vertices);
383  if (minBox.area == mNegOne || box.area < minBox.area)
384  {
385  minBox = box;
386  }
387  }
388  return minBox;
389 }
390 
391 template <typename InputType, typename ComputeType>
394  std::vector<Vector2<ComputeType>> const& vertices)
395 {
396  // The inputs are assumed to be the vertices of a convex polygon that
397  // is counterclockwise ordered. The input points must not contain three
398  // consecutive collinear points.
399 
400  // When the bounding box corresponding to a polygon edge is computed,
401  // we mark the edge as visited. If the edge is encountered later, the
402  // algorithm terminates.
403  std::vector<bool> visited(vertices.size());
404  std::fill(visited.begin(), visited.end(), false);
405 
406  // Start the minimum-area rectangle search with the edge from the last
407  // polygon vertex to the first. When updating the extremes, we want the
408  // bottom-most point on the left edge, the top-most point on the right
409  // edge, the left-most point on the top edge, and the right-most point
410  // on the bottom edge. The polygon edges starting at these points are
411  // then guaranteed not to coincide with a box edge except when an extreme
412  // point is shared by two box edges (at a corner).
413  Box minBox = SmallestBox((int)vertices.size() - 1, 0, vertices);
414  visited[minBox.index[0]] = true;
415 
416  // Execute the rotating calipers algorithm.
417  Box box = minBox;
418  for (size_t i = 0; i < vertices.size(); ++i)
419  {
420  std::array<std::pair<ComputeType, int>, 4> A;
421  int numA;
422  if (!ComputeAngles(vertices, box, A, numA))
423  {
424  // The polygon is a rectangle, so the search is over.
425  break;
426  }
427 
428  // Indirectly sort the A-array.
429  std::array<int, 4> sort = SortAngles(A, numA);
430 
431  // Update the supporting indices (box.index[]) and the box axis
432  // directions (box.U[]).
433  if (!UpdateSupport(A, numA, sort, vertices, visited, box))
434  {
435  // We have already processed the box polygon edge, so the search
436  // is over.
437  break;
438  }
439 
440  if (box.area < minBox.area)
441  {
442  minBox = box;
443  }
444  }
445 
446  return minBox;
447 }
448 
449 template <typename InputType, typename ComputeType>
452  std::vector<Vector2<ComputeType>> const& vertices)
453 {
454  Box box;
455  box.U[0] = vertices[i1] - vertices[i0];
456  box.U[1] = -Perp(box.U[0]);
457  box.index = { i1, i1, i1, i1 };
458  box.sqrLenU0 = Dot(box.U[0], box.U[0]);
459 
460  Vector2<ComputeType> const& origin = vertices[i1];
461  Vector2<ComputeType> support[4];
462  for (int j = 0; j < 4; ++j)
463  {
464  support[j] = { mZero, mZero };
465  }
466 
467  int i = 0;
468  for (auto const& vertex : vertices)
469  {
470  Vector2<ComputeType> diff = vertex - origin;
471  Vector2<ComputeType> v = { Dot(box.U[0], diff), Dot(box.U[1], diff) };
472 
473  // The right-most vertex of the bottom edge is vertices[i1]. The
474  // assumption of no triple of collinear vertices guarantees that
475  // box.index[0] is i1, which is the initial value assigned at the
476  // beginning of this function. Therefore, there is no need to test
477  // for other vertices farther to the right than vertices[i1].
478 
479  if (v[0] > support[1][0] ||
480  (v[0] == support[1][0] && v[1] > support[1][1]))
481  {
482  // New right maximum OR same right maximum but closer to top.
483  box.index[1] = i;
484  support[1] = v;
485  }
486 
487  if (v[1] > support[2][1] ||
488  (v[1] == support[2][1] && v[0] < support[2][0]))
489  {
490  // New top maximum OR same top maximum but closer to left.
491  box.index[2] = i;
492  support[2] = v;
493  }
494 
495  if (v[0] < support[3][0] ||
496  (v[0] == support[3][0] && v[1] < support[3][1]))
497  {
498  // New left minimum OR same left minimum but closer to bottom.
499  box.index[3] = i;
500  support[3] = v;
501  }
502 
503  ++i;
504  }
505 
506  // The comment in the loop has the implication that support[0] = { 0, 0 },
507  // so the scaled height (support[2][1] - support[0][1]) is simply
508  // support[2][1].
509  ComputeType scaledWidth = support[1][0] - support[3][0];
510  ComputeType scaledHeight = support[2][1];
511  box.area = scaledWidth * scaledHeight / box.sqrLenU0;
512  return box;
513 }
514 
515 template <typename InputType, typename ComputeType>
517  std::vector<Vector2<ComputeType>> const& vertices, Box const& box,
518  std::array<std::pair<ComputeType, int>, 4>& A, int& numA) const
519 {
520  int const numVertices = static_cast<int>(vertices.size());
521  numA = 0;
522  for (int k0 = 3, k1 = 0; k1 < 4; k0 = k1++)
523  {
524  if (box.index[k0] != box.index[k1])
525  {
526  // The box edges are ordered in k1 as U[0], U[1], -U[0], -U[1].
528  ((k0 & 2) ? -box.U[k0 & 1] : box.U[k0 & 1]);
529  int j0 = box.index[k0], j1 = j0 + 1;
530  if (j1 == numVertices)
531  {
532  j1 = 0;
533  }
534  Vector2<ComputeType> E = vertices[j1] - vertices[j0];
535  ComputeType dp = DotPerp(D, E);
536  ComputeType esqrlen = Dot(E, E);
537  ComputeType sinThetaSqr = (dp * dp) / esqrlen;
538  A[numA++] = std::make_pair(sinThetaSqr, k0);
539  }
540  }
541  return numA > 0;
542 }
543 
544 template <typename InputType, typename ComputeType>
546  std::array<std::pair<ComputeType, int>, 4> const& A, int numA) const
547 {
548  std::array<int, 4> sort = { 0, 1, 2, 3 };
549  if (numA > 1)
550  {
551  if (numA == 2)
552  {
553  if (A[sort[0]].first > A[sort[1]].first)
554  {
555  std::swap(sort[0], sort[1]);
556  }
557  }
558  else if (numA == 3)
559  {
560  if (A[sort[0]].first > A[sort[1]].first)
561  {
562  std::swap(sort[0], sort[1]);
563  }
564  if (A[sort[0]].first > A[sort[2]].first)
565  {
566  std::swap(sort[0], sort[2]);
567  }
568  if (A[sort[1]].first > A[sort[2]].first)
569  {
570  std::swap(sort[1], sort[2]);
571  }
572  }
573  else // numA == 4
574  {
575  if (A[sort[0]].first > A[sort[1]].first)
576  {
577  std::swap(sort[0], sort[1]);
578  }
579  if (A[sort[2]].first > A[sort[3]].first)
580  {
581  std::swap(sort[2], sort[3]);
582  }
583  if (A[sort[0]].first > A[sort[2]].first)
584  {
585  std::swap(sort[0], sort[2]);
586  }
587  if (A[sort[1]].first > A[sort[3]].first)
588  {
589  std::swap(sort[1], sort[3]);
590  }
591  if (A[sort[1]].first > A[sort[2]].first)
592  {
593  std::swap(sort[1], sort[2]);
594  }
595  }
596  }
597  return sort;
598 }
599 
600 template <typename InputType, typename ComputeType>
602  std::array<std::pair<ComputeType, int>, 4> const& A, int numA,
603  std::array<int, 4> const& sort,
604  std::vector<Vector2<ComputeType>> const& vertices,
605  std::vector<bool>& visited, Box& box)
606 {
607  // Replace the support vertices of those edges attaining minimum angle
608  // with the other endpoints of the edges.
609  int const numVertices = static_cast<int>(vertices.size());
610  auto const& amin = A[sort[0]];
611  for (int k = 0; k < numA; ++k)
612  {
613  auto const& a = A[sort[k]];
614  if (a.first == amin.first)
615  {
616  if (++box.index[a.second] == numVertices)
617  {
618  box.index[a.second] = 0;
619  }
620  }
621  else
622  {
623  break;
624  }
625  }
626 
627  int bottom = box.index[amin.second];
628  if (visited[bottom])
629  {
630  // We have already processed this polygon edge.
631  return false;
632  }
633  visited[bottom] = true;
634 
635  // Cycle the vertices so that the bottom support occurs first.
636  std::array<int, 4> nextIndex;
637  for (int k = 0; k < 4; ++k)
638  {
639  nextIndex[k] = box.index[(amin.second + k) % 4];
640  }
641  box.index = nextIndex;
642 
643  // Compute the box axis directions.
644  int j1 = box.index[0], j0 = j1 - 1;
645  if (j0 < 0)
646  {
647  j0 = numVertices - 1;
648  }
649  box.U[0] = vertices[j1] - vertices[j0];
650  box.U[1] = -Perp(box.U[0]);
651  box.sqrLenU0 = Dot(box.U[0], box.U[0]);
652 
653  // Compute the box area.
654  Vector2<ComputeType> diff[2] =
655  {
656  vertices[box.index[1]] - vertices[box.index[3]],
657  vertices[box.index[2]] - vertices[box.index[0]]
658  };
659  box.area = Dot(box.U[0], diff[0]) * Dot(box.U[1], diff[1]) / box.sqrLenU0;
660  return true;
661 }
662 
663 template <typename InputType, typename ComputeType>
665  std::vector<Vector2<ComputeType>> const& computePoints,
666  OrientedBox2<InputType>& itMinBox)
667 {
668  // The sum, difference, and center are all computed exactly.
669  Vector2<ComputeType> sum[2] =
670  {
671  computePoints[minBox.index[1]] + computePoints[minBox.index[3]],
672  computePoints[minBox.index[2]] + computePoints[minBox.index[0]]
673  };
674 
675  Vector2<ComputeType> difference[2] =
676  {
677  computePoints[minBox.index[1]] - computePoints[minBox.index[3]],
678  computePoints[minBox.index[2]] - computePoints[minBox.index[0]]
679  };
680 
681  Vector2<ComputeType> center = mHalf * (
682  Dot(minBox.U[0], sum[0]) * minBox.U[0] +
683  Dot(minBox.U[1], sum[1]) * minBox.U[1]) / minBox.sqrLenU0;
684 
685  // Calculate the squared extent using ComputeType to avoid loss of
686  // precision before computing a squared root.
687  Vector2<ComputeType> sqrExtent;
688  for (int i = 0; i < 2; ++i)
689  {
690  sqrExtent[i] = mHalf * Dot(minBox.U[i], difference[i]);
691  sqrExtent[i] *= sqrExtent[i];
692  sqrExtent[i] /= minBox.sqrLenU0;
693  }
694 
695  for (int i = 0; i < 2; ++i)
696  {
697  itMinBox.center[i] = (InputType)center[i];
698  itMinBox.extent[i] = sqrt((InputType)sqrExtent[i]);
699 
700  // Before converting to floating-point, factor out the maximum
701  // component using ComputeType to generate rational numbers in a
702  // range that avoids loss of precision during the conversion and
703  // normalization.
704  Vector2<ComputeType> const& axis = minBox.U[i];
705  ComputeType cmax = std::max(std::abs(axis[0]), std::abs(axis[1]));
706  ComputeType invCMax = mOne / cmax;
707  for (int j = 0; j < 2; ++j)
708  {
709  itMinBox.axis[i][j] = (InputType)(axis[j] * invCMax);
710  }
711  Normalize(itMinBox.axis[i]);
712  }
713 
714  mSupportIndices = minBox.index;
715  mArea = (InputType)minBox.area;
716 }
717 
718 
719 }
std::vector< int > const & GetHull() const
Box SmallestBox(int i0, int i1, std::vector< Vector2< ComputeType >> const &vertices)
std::array< Vector< N, Real >, N > axis
gte::BSNumber< UIntegerType > abs(gte::BSNumber< UIntegerType > const &number)
Definition: GteBSNumber.h:966
void ConvertTo(Box const &minBox, std::vector< Vector2< ComputeType >> const &computePoints, OrientedBox2< InputType > &itMinBox)
Box ComputeBoxForEdgeOrderN(std::vector< Vector2< ComputeType >> const &vertices)
std::array< int, 4 > SortAngles(std::array< std::pair< ComputeType, int >, 4 > const &A, int numA) const
std::array< int, 4 > index
std::array< int, 4 > const & GetSupportIndices() const
Vector2< InputType > const * mPoints
PrimalQuery2< ComputeType > const & GetQuery() const
GLsizei const GLfloat * value
Definition: glcorearb.h:819
InputType GetArea() const
bool ComputeAngles(std::vector< Vector2< ComputeType >> const &vertices, Box const &box, std::array< std::pair< ComputeType, int >, 4 > &A, int &numA) const
Line2< InputType > const & GetLine() const
Vector< N, Real > direction
Definition: GteLine.h:29
Vector< N, Real > extent
GLboolean GLboolean GLboolean GLboolean a
Definition: glcorearb.h:1217
Vector2< InputType > const * GetPoints() const
std::vector< int > const & GetHull() const
GLfixed GLfixed GLint GLint GLfixed points
Definition: glext.h:4927
std::vector< int > mHull
Vector2< ComputeType > U[2]
Vector2< Real > const * GetVertices() const
GLsizei GLenum const void * indices
Definition: glcorearb.h:401
int GetDimension() const
OrientedBox2< InputType > operator()(int numPoints, Vector2< InputType > const *points, bool useRotatingCalipers=!std::is_floating_point< ComputeType >::value)
static Vector Zero()
GLint first
Definition: glcorearb.h:400
Real DotPerp(Vector2< Real > const &v0, Vector2< Real > const &v1)
Definition: GteVector2.h:117
void RemoveCollinearPoints(std::vector< Vector2< ComputeType >> &vertices)
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
Real Normalize(GVector< Real > &v, bool robust=false)
Definition: GteGVector.h:454
GLdouble GLdouble t
Definition: glext.h:239
bool UpdateSupport(std::array< std::pair< ComputeType, int >, 4 > const &A, int numA, std::array< int, 4 > const &sort, std::vector< Vector2< ComputeType >> const &vertices, std::vector< bool > &visited, Box &box)
Vector2< Real > Perp(Vector2< Real > const &v)
Definition: GteVector2.h:103
GLfloat GLfloat GLfloat GLfloat h
Definition: glcorearb.h:1997
GLenum array
Definition: glext.h:6669
const GLdouble * v
Definition: glcorearb.h:832
Box ComputeBoxForEdgeOrderNSqr(std::vector< Vector2< ComputeType >> const &vertices)
std::array< int, 4 > mSupportIndices
Vector< N, Real > origin
Definition: GteLine.h:29
GLint GLint bottom
Definition: glcorearb.h:2000
Vector< N, Real > center
static Vector Unit(int d)


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