GteIntrEllipse2Ellipse2.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 #include <LowLevel/GteLogger.h>
14 #include <Mathematics/GteSegment.h>
16 #include <Mathematics/GteFIQuery.h>
17 #include <Mathematics/GteTIQuery.h>
21 
22 // The test-intersection and find-intersection queries implemented here are
23 // discussed in the document
24 // http://www.geometrictools.com/Documentation/IntersectionOfEllipses.pdf
25 // The Real type should support exact rational arithmetic in order for the
26 // polynomial root construction to be robust. The classification of the
27 // intersections depends on various sign tests of computed values. If these
28 // values are computed with floating-point arithmetic, the sign tests can
29 // lead to misclassification.
30 //
31 // The area-of-intersection query is discussed in the document
32 // http://www.geometrictools.com/Documentation/AreaIntersectingEllipses.pdf
33 
34 namespace gte
35 {
36 
37 template <typename Real>
38 class TIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>
39 {
40 public:
41  // The query tests the relationship between the ellipses as solid
42  // objects.
43  enum
44  {
52  ELLIPSES_EQUAL
53  };
54 
55  // The ellipse axes are already normalized, which most likely introduced
56  // rounding errors.
57  int operator()(Ellipse2<Real> const& ellipse0,
58  Ellipse2<Real> const& ellipse1);
59 
60 private:
61  void GetRoots(Real d0, Real c0, int& numRoots, Real* roots);
62  void GetRoots(Real d0, Real d1, Real c0, Real c1, int& numRoots,
63  Real* roots);
64 
65  int Classify(Real minSqrDistance, Real maxSqrDistance, Real d0c0pd1c1);
66 };
67 
68 template <typename Real>
69 class FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>
70 {
71 public:
72  // The queries find the intersections (if any) of the ellipses treated as
73  // hollow objects. The implementations use the same concepts.
74  FIQuery();
75 
76  struct Result
77  {
78  // This value is true when the ellipses intersect in at least one
79  // point.
80  bool intersect;
81 
82  // If the ellipses are not the same, numPoints is 0 through 4 and
83  // that number of elements of 'points' are valid. If the ellipses
84  // are the same, numPoints is set to maxInt and 'points' is invalid.
85  int numPoints;
86  std::array<Vector2<Real>, 4> points;
87  std::array<bool, 4> isTransverse;
88  };
89 
90  // The ellipse axes are already normalized, which most likely introduced
91  // rounding errors.
92  Result operator()(Ellipse2<Real> const& ellipse0,
93  Ellipse2<Real> const& ellipse1);
94 
95  // The axis directions do not have to be unit length. The quadratic
96  // equations are constructed according to the details of the PDF document
97  // about the intersection of ellipses.
98  Result operator()(Vector2<Real> const& center0,
99  Vector2<Real> const axis0[2], Vector2<Real> const& sqrExtent0,
100  Vector2<Real> const& center1, Vector2<Real> const axis1[2],
101  Vector2<Real> const& sqrExtent1);
102 
103 
104  // Compute the area of intersection of ellipses.
105  struct AreaResult
106  {
107  // The configuration of the two ellipses.
108  enum
109  {
115  FOUR_CHORD_REGION
116  };
117 
118  // One of the enumerates, determined in the call to AreaDispatch.
120 
121  // Information about the ellipse-ellipse intersection points.
122  Result findResult;
123 
124  // The area of intersection of the ellipses.
125  Real area;
126  };
127 
128  // The ellipse axes are already normalized, which most likely introduced
129  // rounding errors.
130  AreaResult AreaOfIntersection(Ellipse2<Real> const& ellipse0,
131  Ellipse2<Real> const& ellipse1);
132 
133  // The axis directions do not have to be unit length. The positive
134  // definite matrices are constructed according to the details of the PDF
135  // documentabout the intersection of ellipses.
136  AreaResult AreaOfIntersection(Vector2<Real> const& center0,
137  Vector2<Real> const axis0[2], Vector2<Real> const& sqrExtent0,
138  Vector2<Real> const& center1, Vector2<Real> const axis1[2],
139  Vector2<Real> const& sqrExtent1);
140 
141 private:
142  // Compute the coefficients of the quadratic equation but with the
143  // y^2-coefficient of 1.
144  void ToCoefficients(Vector2<Real> const& center,
145  Vector2<Real> const axis[2], Vector2<Real> const& SqrExtent,
146  std::array<Real, 5>& coeff);
147 
148  void DoRootFinding(Result& result);
149  void D4NotZeroEBarNotZero(Result& result);
150  void D4NotZeroEBarZero(Real const& xbar, Result& result);
151  void D4ZeroD2NotZeroE2NotZero(Result& result);
152  void D4ZeroD2NotZeroE2Zero(Result& result);
153  void D4ZeroD2Zero(Result& result);
154 
155  // Helper function for D4ZeroD2Zero.
156  void SpecialIntersection(Real const& x, bool transverse, Result& result);
157 
158 
159  // Helper functions for AreaOfIntersection.
160  struct EllipseInfo
161  {
163  std::array<Vector2<Real>, 2> axis;
166  Real AB; // extent[0] * extent[1]
167  Real halfAB; // extent[0] * extent[1] / 2
168  Real BpA; // extent[1] + extent[0]
169  Real BmA; // extent[1] - extent[0]
170  };
171 
172  // The axis, extent, and sqrExtent members of E must be set before this
173  // function is called.
174  void FinishEllipseInfo(EllipseInfo& E);
175 
176  void AreaDispatch(EllipseInfo const& E0, EllipseInfo const& E1,
177  AreaResult& ar);
178 
179  void AreaCS(EllipseInfo const& E0, EllipseInfo const& E1,
180  AreaResult& ar);
181 
182  void Area2(EllipseInfo const& E0, EllipseInfo const& E1, int i0, int i1,
183  AreaResult& ar);
184 
185  void Area4(EllipseInfo const& E0, EllipseInfo const& E1,
186  AreaResult& ar);
187 
188  Real ComputeAreaChordRegion(EllipseInfo const& E,
189  Vector2<Real> const& P0mC, Vector2<Real> const& P1mC);
190 
191  Real ComputeIntegral(EllipseInfo const& E, Real const& theta);
192 
193 
194  // Constants that are set up once (optimization for rational arithmetic).
195  Real mZero, mOne, mTwo, mPi, mTwoPi;
196 
197  // Various polynomial coefficients. The short names are meant to match
198  // the variable names used in the PDF documentation.
199  std::array<Real, 5> mA, mB, mD, mF;
200  std::array<Real, 3> mC, mE;
201  Real mA2Div2, mA4Div2;
202 };
203 
204 // Template aliases for convenience.
205 template <typename Real>
207 
208 template <typename Real>
209 using FIEllipses2 = FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>;
210 
211 
212 // TIQuery for intersections
213 
214 template <typename Real>
215 int TIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::operator()(
216  Ellipse2<Real> const& ellipse0, Ellipse2<Real> const& ellipse1)
217 {
218  Real const zero = 0, one = 1;
219 
220  // Get the parameters of ellipe0.
221  Vector2<Real> K0 = ellipse0.center;
222  Matrix2x2<Real> R0;
223  R0.SetCol(0, ellipse0.axis[0]);
224  R0.SetCol(1, ellipse0.axis[1]);
225  Matrix2x2<Real> D0{
226  one / (ellipse0.extent[0] * ellipse0.extent[0]), zero,
227  zero, one / (ellipse0.extent[1] * ellipse0.extent[1]) };
228 
229  // Get the parameters of ellipse1.
230  Vector2<Real> K1 = ellipse1.center;
231  Matrix2x2<Real> R1;
232  R1.SetCol(0, ellipse1.axis[0]);
233  R1.SetCol(1, ellipse1.axis[1]);
234  Matrix2x2<Real> D1{
235  one / (ellipse1.extent[0] * ellipse1.extent[0]), zero,
236  zero, one / (ellipse1.extent[1] * ellipse1.extent[1]) };
237 
238  // Compute K2.
239  Matrix2x2<Real> D0NegHalf{
240  ellipse0.extent[0], zero,
241  zero, ellipse0.extent[1] };
242  Matrix2x2<Real> D0Half{
243  one / ellipse0.extent[0], zero,
244  zero, one / ellipse0.extent[1] };
245  Vector2<Real> K2 = D0Half*((K1 - K0)*R0);
246 
247  // Compute M2.
248  Matrix2x2<Real> R1TR0D0NegHalf = MultiplyATB(R1, R0 * D0NegHalf);
249  Matrix2x2<Real> M2 = MultiplyATB(R1TR0D0NegHalf, D1) * R1TR0D0NegHalf;
250 
251  // Factor M2 = R*D*R^T.
253  std::array<Real, 2> D;
254  std::array<std::array<Real, 2>, 2> evec;
255  es(M2(0, 0), M2(0, 1), M2(1, 1), +1, D, evec);
256  Matrix2x2<Real> R;
257  R.SetCol(0, evec[0]);
258  R.SetCol(1, evec[1]);
259 
260  // Compute K = R^T*K2.
261  Vector2<Real> K = K2 * R;
262 
263  // Transformed ellipse0 is Z^T*Z = 1 and transformed ellipse1 is
264  // (Z-K)^T*D*(Z-K) = 0.
265 
266  // The minimum and maximum squared distances from the origin of points on
267  // transformed ellipse1 are used to determine whether the ellipses
268  // intersect, are separated, or one contains the other.
269  Real minSqrDistance = std::numeric_limits<Real>::max();
270  Real maxSqrDistance = zero;
271 
272  if (K == Vector2<Real>::Zero())
273  {
274  // The special case of common centers must be handled separately. It
275  // is not possible for the ellipses to be separated.
276  for (int i = 0; i < 2; ++i)
277  {
278  Real invD = one / D[i];
279  if (invD < minSqrDistance)
280  {
281  minSqrDistance = invD;
282  }
283  if (invD > maxSqrDistance)
284  {
285  maxSqrDistance = invD;
286  }
287  }
288  return Classify(minSqrDistance, maxSqrDistance, zero);
289  }
290 
291  // The closest point P0 and farthest point P1 are solutions to
292  // s0*D*(P0 - K) = P0 and s1*D1*(P1 - K) = P1 for some scalars s0 and s1
293  // that are roots to the function
294  // f(s) = d0*k0^2/(d0*s-1)^2 + d1*k1^2/(d1*s-1)^2 - 1
295  // where D = diagonal(d0,d1) and K = (k0,k1).
296  Real d0 = D[0], d1 = D[1];
297  Real c0 = K[0] * K[0], c1 = K[1] * K[1];
298 
299  // Sort the values so that d0 >= d1. This allows us to bound the roots of
300  // f(s), of which there are at most 4.
301  std::vector<std::pair<Real, Real>> param(2);
302  if (d0 >= d1)
303  {
304  param[0] = std::make_pair(d0, c0);
305  param[1] = std::make_pair(d1, c1);
306  }
307  else
308  {
309  param[0] = std::make_pair(d1, c1);
310  param[1] = std::make_pair(d0, c0);
311  }
312 
313  std::vector<std::pair<Real, Real>> valid;
314  valid.reserve(2);
315  if (param[0].first > param[1].first)
316  {
317  // d0 > d1
318  for (int i = 0; i < 2; ++i)
319  {
320  if (param[i].second > zero)
321  {
322  valid.push_back(param[i]);
323  }
324  }
325  }
326  else
327  {
328  // d0 = d1
329  param[0].second += param[1].second;
330  if (param[0].second > zero)
331  {
332  valid.push_back(param[0]);
333  }
334  }
335 
336  size_t numValid = valid.size();
337  int numRoots = 0;
338  Real roots[4];
339  if (numValid == 2)
340  {
341  GetRoots(valid[0].first, valid[1].first, valid[0].second,
342  valid[1].second, numRoots, roots);
343  }
344  else if (numValid == 1)
345  {
346  GetRoots(valid[0].first, valid[0].second, numRoots, roots);
347  }
348  // else: numValid cannot be zero because we already handled case K = 0
349 
350  for (int i = 0; i < numRoots; ++i)
351  {
352  Real s = roots[i];
353  Real p0 = d0 * K[0] * s / (d0 * s - (Real)1);
354  Real p1 = d1 * K[1] * s / (d1 * s - (Real)1);
355  Real sqrDistance = p0 * p0 + p1 * p1;
356  if (sqrDistance < minSqrDistance)
357  {
358  minSqrDistance = sqrDistance;
359  }
360  if (sqrDistance > maxSqrDistance)
361  {
362  maxSqrDistance = sqrDistance;
363  }
364  }
365 
366  return Classify(minSqrDistance, maxSqrDistance, d0 * c0 + d1 * c1);
367 }
368 
369 template <typename Real>
370 void TIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::GetRoots(Real d0, Real c0,
371  int& numRoots, Real* roots)
372 {
373  // f(s) = d0*c0/(d0*s-1)^2 - 1
374  Real const one = (Real)1;
375  Real temp = sqrt(d0*c0);
376  Real inv = one / d0;
377  numRoots = 2;
378  roots[0] = (one - temp) * inv;
379  roots[1] = (one + temp) * inv;
380 }
381 
382 template <typename Real>
383 void TIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::GetRoots(Real d0, Real d1,
384  Real c0, Real c1, int& numRoots, Real* roots)
385 {
386  // f(s) = d0*c0/(d0*s-1)^2 + d1*c1/(d1*s-1)^2 - 1
387  // with d0 > d1
388 
389  Real const zero = 0, one = (Real)1;
390  Real d0c0 = d0 * c0;
391  Real d1c1 = d1 * c1;
392  Real sum = d0c0 + d1c1;
393  Real sqrtsum = sqrt(sum);
394 
395  std::function<Real(Real)> F = [&one, d0, d1, d0c0, d1c1](Real s)
396  {
397  Real invN0 = one / (d0*s - one);
398  Real invN1 = one / (d1*s - one);
399  Real term0 = d0c0 * invN0 * invN0;
400  Real term1 = d1c1 * invN1 * invN1;
401  Real f = term0 + term1 - one;
402  return f;
403  };
404 
405  std::function<Real(Real)> DF = [&one, d0, d1, d0c0, d1c1](Real s)
406  {
407  Real const two = 2;
408  Real invN0 = one / (d0*s - one);
409  Real invN1 = one / (d1*s - one);
410  Real term0 = d0 * d0c0 * invN0 * invN0 * invN0;
411  Real term1 = d1 * d1c1 * invN1 * invN1 * invN1;
412  Real df = -two * (term0 + term1);
413  return df;
414  };
415 
416  unsigned int const maxIterations = (unsigned int)(
417  3 + std::numeric_limits<Real>::digits -
418  std::numeric_limits<Real>::min_exponent);
419  unsigned int iterations;
420  numRoots = 0;
421 
422  Real invD0 = one / d0;
423  Real invD1 = one / d1;
424  Real smin, smax, s, fval;
425 
426  // Compute root in (-infinity,1/d0). Obtain a lower bound for the root
427  // better than -std::numeric_limits<Real>::max().
428  smax = invD0;
429  fval = sum - one;
430  if (fval > zero)
431  {
432  smin = (one - sqrtsum) * invD1; // < 0
433  fval = F(smin);
434  LogAssert(fval <= zero, "Unexpected condition.");
435  }
436  else
437  {
438  smin = zero;
439  }
440  iterations = RootsBisection<Real>::Find(F, smin, smax, -one, one,
441  maxIterations, s);
442  fval = F(s);
443  LogAssert(iterations > 0, "Unexpected condition.");
444  roots[numRoots++] = s;
445 
446  // Compute roots (if any) in (1/d0,1/d1). It is the case that
447  // F(1/d0) = +infinity, F'(1/d0) = -infinity
448  // F(1/d1) = +infinity, F'(1/d1) = +infinity
449  // F"(s) > 0 for all s in the domain of F
450  // Compute the unique root r of F'(s) on (1/d0,1/d1). The bisector needs
451  // only the signs at the endpoints, so we pass -1 and +1 instead of the
452  // infinite values. If F(r) < 0, F(s) has two roots in the interval.
453  // If F(r) = 0, F(s) has only one root in the interval.
454  Real const oneThird = (Real)(1.0 / 3.0);
455  Real rho = pow(d0 * d0c0 / (d1 * d1c1), oneThird);
456  Real smid = (one + rho) / (d0 + rho * d1);
457  Real fmid = F(smid);
458  if (fmid <= zero)
459  {
460  // Pass in signs rather than infinities, because the bisector cares
461  // only about the signs.
462  iterations = RootsBisection<Real>::Find(F, invD0, smid, one, -one,
463  maxIterations, s);
464  fval = F(s);
465  LogAssert(iterations > 0, "Unexpected condition.");
466  roots[numRoots++] = s;
467  iterations = RootsBisection<Real>::Find(F, smid, invD1, -one, one,
468  maxIterations, s);
469  fval = F(s);
470  LogAssert(iterations > 0, "Unexpected condition.");
471  roots[numRoots++] = s;
472  }
473  else if (fmid == zero)
474  {
475  roots[numRoots++] = smid;
476  }
477 
478  // Compute root in (1/d1,+infinity). Obtain an upper bound for the root
479  // better than std::numeric_limits<Real>::max().
480  smin = invD1;
481  smax = (one + sqrtsum) * invD1; // > 1/d1
482  fval = F(smax);
483  LogAssert(fval <= zero, "Unexpected condition.");
484  iterations = RootsBisection<Real>::Find(F, smin, smax, one, -one,
485  maxIterations, s);
486  fval = F(s);
487  LogAssert(iterations > 0, "Unexpected condition.");
488  roots[numRoots++] = s;
489 }
490 
491 template <typename Real>
492 int TIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::Classify(
493  Real minSqrDistance, Real maxSqrDistance, Real d0c0pd1c1)
494 {
495  Real const one = (Real)1;
496 
497  if (maxSqrDistance < one)
498  {
499  return ELLIPSE0_STRICTLY_CONTAINS_ELLIPSE1;
500  }
501  else if (maxSqrDistance > one)
502  {
503  if (minSqrDistance < one)
504  {
505  return ELLIPSES_OVERLAP;
506  }
507  else if (minSqrDistance > one)
508  {
509  if (d0c0pd1c1 > one)
510  {
511  return ELLIPSES_SEPARATED;
512  }
513  else
514  {
515  return ELLIPSE1_STRICTLY_CONTAINS_ELLIPSE0;
516  }
517  }
518  else // minSqrDistance = 1
519  {
520  if (d0c0pd1c1 > one)
521  {
522  return ELLIPSE0_OUTSIDE_ELLIPSE1_BUT_TANGENT;
523  }
524  else
525  {
526  return ELLIPSE1_CONTAINS_ELLIPSE0_BUT_TANGENT;
527  }
528  }
529  }
530  else // maxSqrDistance = 1
531  {
532  if (minSqrDistance < one)
533  {
534  return ELLIPSE0_CONTAINS_ELLIPSE1_BUT_TANGENT;
535  }
536  else // minSqrDistance = 1
537  {
538  return ELLIPSES_EQUAL;
539  }
540  }
541 }
542 
543 
544 
545 // FIQuery constructor for both intersection and area queries.
546 
547 template <typename Real>
549  :
550  mZero((Real)0),
551  mOne((Real)1),
552  mTwo((Real)2),
553  mPi((Real)GTE_C_PI),
554  mTwoPi((Real)GTE_C_TWO_PI)
555 {
556 }
557 
558 
559 
560 // FIQuery functions for ellipse-ellipse intersection points.
561 
562 template <typename Real>
563 typename FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::Result
564 FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::operator()(
565  Ellipse2<Real> const& ellipse0, Ellipse2<Real> const& ellipse1)
566 {
567  Vector2<Real> rCenter, rAxis[2], rSqrExtent;
568 
569  rCenter = { ellipse0.center[0], ellipse0.center[1] };
570  rAxis[0] = { ellipse0.axis[0][0], ellipse0.axis[0][1] };
571  rAxis[1] = { ellipse0.axis[1][0], ellipse0.axis[1][1] };
572  rSqrExtent =
573  {
574  ellipse0.extent[0] * ellipse0.extent[0],
575  ellipse0.extent[1] * ellipse0.extent[1]
576  };
577  ToCoefficients(rCenter, rAxis, rSqrExtent, mA);
578 
579  rCenter = { ellipse1.center[0], ellipse1.center[1] };
580  rAxis[0] = { ellipse1.axis[0][0], ellipse1.axis[0][1] };
581  rAxis[1] = { ellipse1.axis[1][0], ellipse1.axis[1][1] };
582  rSqrExtent =
583  {
584  ellipse1.extent[0] * ellipse1.extent[0],
585  ellipse1.extent[1] * ellipse1.extent[1]
586  };
587  ToCoefficients(rCenter, rAxis, rSqrExtent, mB);
588 
589  Result result;
590  DoRootFinding(result);
591  return result;
592 }
593 
594 template <typename Real>
595 typename FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::Result
596 FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::operator()(
597  Vector2<Real> const& center0, Vector2<Real> const axis0[2],
598  Vector2<Real> const& sqrExtent0, Vector2<Real> const& center1,
599  Vector2<Real> const axis1[2], Vector2<Real> const& sqrExtent1)
600 {
601  Vector2<Real> rCenter, rAxis[2], rSqrExtent;
602 
603  rCenter = { center0[0], center0[1] };
604  rAxis[0] = { axis0[0][0], axis0[0][1] };
605  rAxis[1] = { axis0[1][0], axis0[1][1] };
606  rSqrExtent = { sqrExtent0[0], sqrExtent0[1] };
607  ToCoefficients(rCenter, rAxis, rSqrExtent, mA);
608 
609  rCenter = { center1[0], center1[1] };
610  rAxis[0] = { axis1[0][0], axis1[0][1] };
611  rAxis[1] = { axis1[1][0], axis1[1][1] };
612  rSqrExtent = { sqrExtent1[0], sqrExtent1[1] };
613  ToCoefficients(rCenter, rAxis, rSqrExtent, mB);
614 
615  Result result;
616  DoRootFinding(result);
617  return result;
618 }
619 
620 template <typename Real>
621 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::ToCoefficients(
622  Vector2<Real> const& center, Vector2<Real> const axis[2],
623  Vector2<Real> const& sqrExtent, std::array<Real, 5>& coeff)
624 {
625  Real denom0 = Dot(axis[0], axis[0]) * sqrExtent[0];
626  Real denom1 = Dot(axis[1], axis[1]) * sqrExtent[1];
627  Matrix2x2<Real> outer0 = OuterProduct(axis[0], axis[0]);
628  Matrix2x2<Real> outer1 = OuterProduct(axis[1], axis[1]);
629  Matrix2x2<Real> A = outer0 / denom0 + outer1 / denom1;
630  Vector2<Real> product = A * center;
631  Vector2<Real> B = -mTwo * product;
632  Real const& denom = A(1, 1);
633  coeff[0] = (Dot(center, product) - mOne) / denom;
634  coeff[1] = B[0] / denom;
635  coeff[2] = B[1] / denom;
636  coeff[3] = A(0, 0) / denom;
637  coeff[4] = mTwo * A(0, 1) / denom;
638  // coeff[5] = A(1, 1) / denom = 1;
639 }
640 
641 template <typename Real>
642 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::DoRootFinding(
643  Result& result)
644 {
645  bool allZero = true;
646  for (int i = 0; i < 5; ++i)
647  {
648  mD[i] = mA[i] - mB[i];
649  if (mD[i] != mZero)
650  {
651  allZero = false;
652  }
653  }
654  if (allZero)
655  {
656  result.intersect = false;
657  result.numPoints = std::numeric_limits<int>::max();
658  return;
659  }
660 
661  result.numPoints = 0;
662 
663  mA2Div2 = mA[2] / mTwo;
664  mA4Div2 = mA[4] / mTwo;
665  mC[0] = mA[0] - mA2Div2 * mA2Div2;
666  mC[1] = mA[1] - mA2Div2 * mA[4];
667  mC[2] = mA[3] - mA4Div2 * mA4Div2; // c[2] > 0
668  mE[0] = mD[0] - mA2Div2 * mD[2];
669  mE[1] = mD[1] - mA2Div2 * mD[4] - mA4Div2 * mD[2];
670  mE[2] = mD[3] - mA4Div2 * mD[4];
671 
672  if (mD[4] != mZero)
673  {
674  Real xbar = -mD[2] / mD[4];
675  Real ebar = mE[0] + xbar * (mE[1] + xbar * mE[2]);
676  if (ebar != mZero)
677  {
678  D4NotZeroEBarNotZero(result);
679  }
680  else
681  {
682  D4NotZeroEBarZero(xbar, result);
683  }
684  }
685  else if (mD[2] != mZero) // d[4] = 0
686  {
687  if (mE[2] != mZero)
688  {
689  D4ZeroD2NotZeroE2NotZero(result);
690  }
691  else
692  {
693  D4ZeroD2NotZeroE2Zero(result);
694  }
695  }
696  else // d[2] = d[4] = 0
697  {
698  D4ZeroD2Zero(result);
699  }
700 
701  result.intersect = (result.numPoints > 0);
702 }
703 
704 template <typename Real>
705 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::D4NotZeroEBarNotZero(
706  Result& result)
707 {
708  // The graph of w = -e(x)/d(x) is a hyperbola.
709  Real d2d2 = mD[2] * mD[2], d2d4 = mD[2] * mD[4], d4d4 = mD[4] * mD[4];
710  Real e0e0 = mE[0] * mE[0], e0e1 = mE[0] * mE[1], e0e2 = mE[0] * mE[2];
711  Real e1e1 = mE[1] * mE[1], e1e2 = mE[1] * mE[2], e2e2 = mE[2] * mE[2];
712  std::array<Real, 5> f =
713  {
714  mC[0] * d2d2 + e0e0,
715  mC[1] * d2d2 + mTwo * (mC[0] * d2d4 + e0e1),
716  mC[2] * d2d2 + mC[0] * d4d4 + e1e1 + mTwo * (mC[1] * d2d4 + e0e2),
717  mC[1] * d4d4 + mTwo * (mC[2] * d2d4 + e1e2),
718  mC[2] * d4d4 + e2e2 // > 0
719  };
720 
721  std::map<Real, int> rmMap;
722  RootsPolynomial<Real>::template SolveQuartic<Real>(f[0], f[1], f[2],
723  f[3], f[4], rmMap);
724 
725  // xbar cannot be a root of f(x), so d(x) != 0 and we can solve
726  // directly for w = -e(x)/d(x).
727  for (auto const& rm : rmMap)
728  {
729  Real const& x = rm.first;
730  Real w = -(mE[0] + x * (mE[1] + x * mE[2])) / (mD[2] + mD[4] * x);
731  Real y = w - (mA2Div2 + x * mA4Div2);
732  result.points[result.numPoints] = { x, y };
733  result.isTransverse[result.numPoints++] = (rm.second == 1);
734  }
735 }
736 
737 template <typename Real>
738 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::D4NotZeroEBarZero(
739  Real const& xbar, Result& result)
740 {
741  // Factor e(x) = (d2 + d4*x)*(h0 + h1*x). The w-equation has
742  // two solution components, x = xbar and w = -(h0 + h1*x).
743  Real translate, w, y;
744 
745  // Compute intersection of x = xbar with ellipse.
746  Real ncbar = -(mC[0] + xbar * (mC[1] + xbar * mC[2]));
747  if (ncbar >= mZero)
748  {
749  translate = mA2Div2 + xbar * mA4Div2;
750  w = Function<Real>::Sqrt(ncbar);
751  y = w - translate;
752  result.points[result.numPoints] = { xbar, y };
753  if (w > mZero)
754  {
755  result.isTransverse[result.numPoints++] = true;
756  w = -w;
757  y = w - translate;
758  result.points[result.numPoints] = { xbar, y };
759  result.isTransverse[result.numPoints++] = true;
760  }
761  else
762  {
763  result.isTransverse[result.numPoints++] = false;
764  }
765  }
766 
767  // Compute intersections of w = -(h0 + h1*x) with ellipse.
768  std::array<Real, 2> h;
769  h[1] = mE[2] / mD[4];
770  h[0] = (mE[1] - mD[2] * h[1]) / mD[4];
771  std::array<Real, 3> f =
772  {
773  mC[0] + h[0] * h[0],
774  mC[1] + mTwo * h[0] * h[1],
775  mC[2] + h[1] * h[1] // > 0
776  };
777 
778  std::map<Real, int> rmMap;
779  RootsPolynomial<Real>::template SolveQuadratic<Real>(f[0], f[1], f[2],
780  rmMap);
781  for (auto const& rm : rmMap)
782  {
783  Real const& x = rm.first;
784  translate = mA2Div2 + x * mA4Div2;
785  w = -(h[0] + x * h[1]);
786  y = w - translate;
787  result.points[result.numPoints] = { x, y };
788  result.isTransverse[result.numPoints++] = (rm.second == 1);
789  }
790 }
791 
792 template <typename Real>
793 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::D4ZeroD2NotZeroE2NotZero(
794  Result& result)
795 {
796  Real d2d2 = mD[2] * mD[2];
797  std::array<Real, 5> f =
798  {
799  mC[0] * d2d2 + mE[0] * mE[0],
800  mC[1] * d2d2 + mTwo * mE[0] * mE[1],
801  mC[2] * d2d2 + mE[1] * mE[1] + mTwo * mE[0] * mE[2],
802  mTwo * mE[1] * mE[2],
803  mE[2] * mE[2] // > 0
804  };
805 
806  std::map<Real, int> rmMap;
807  RootsPolynomial<Real>::template SolveQuartic<Real>(f[0], f[1], f[2], f[3],
808  f[4], rmMap);
809  for (auto const& rm : rmMap)
810  {
811  Real const& x = rm.first;
812  Real translate = mA2Div2 + x * mA4Div2;
813  Real w = -(mE[0] + x * (mE[1] + x * mE[2])) / mD[2];
814  Real y = w - translate;
815  result.points[result.numPoints] = { x, y };
816  result.isTransverse[result.numPoints++] = (rm.second == 1);
817  }
818 }
819 
820 template <typename Real>
821 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::D4ZeroD2NotZeroE2Zero(
822  Result& result)
823 {
824  Real d2d2 = mD[2] * mD[2];
825  std::array<Real, 3> f =
826  {
827  mC[0] * d2d2 + mE[0] * mE[0],
828  mC[1] * d2d2 + mTwo * mE[0] * mE[1],
829  mC[2] * d2d2 + mE[1] * mE[1]
830  };
831 
832  std::map<Real, int> rmMap;
833  RootsPolynomial<Real>::template SolveQuadratic<Real>(f[0], f[1], f[2],
834  rmMap);
835  for (auto const& rm : rmMap)
836  {
837  Real const& x = rm.first;
838  Real translate = mA2Div2 + x * mA4Div2;
839  Real w = -(mE[0] + x * mE[1]) / mD[2];
840  Real y = w - translate;
841  result.points[result.numPoints] = { x, y };
842  result.isTransverse[result.numPoints++] = (rm.second == 1);
843  }
844 }
845 
846 template <typename Real>
847 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::D4ZeroD2Zero(
848  Result& result)
849 {
850  // e(x) cannot be identically zero, because if it were, then all
851  // d[i] = 0. But we tested that case previously and exited.
852 
853  if (mE[2] != mZero)
854  {
855  // Make e(x) monic, f(x) = e(x)/e2 = x^2 + (e1/e2)*x + (e0/e2)
856  // = x^2 + f1*x + f0.
857  std::array<Real, 2> f = { mE[0] / mE[2], mE[1] / mE[2] };
858 
859  Real mid = -f[1] / mTwo;
860  Real discr = mid * mid - f[0];
861  if (discr > mZero)
862  {
863  // The theoretical roots of e(x) are x = -f1/2 + s*sqrt(discr)
864  // where s in {-1,+1}. For each root, determine exactly the
865  // sign of c(x). We need c(x) <= 0 in order to solve for
866  // w^2 = -c(x). At the root,
867  // c(x) = c0 + c1*x + c2*x^2 = c0 + c1*x - c2*(f0 + f1*x)
868  // = (c0 - c2*f0) + (c1 - c2*f1)*x
869  // = g0 + g1*x
870  // We need g0 + g1*x <= 0.
871  Real sqrtDiscr = Function<Real>::Sqrt(discr);
872  std::array<Real, 2> g =
873  {
874  mC[0] - mC[2] * f[0],
875  mC[1] - mC[2] * f[1]
876  };
877 
878  if (g[1] > mZero)
879  {
880  // We need s*sqrt(discr) <= -g[0]/g[1] + f1/2.
881  Real r = -g[0] / g[1] - mid;
882 
883  // s = +1:
884  if (r >= mZero)
885  {
886  Real rsqr = r * r;
887  if (discr < rsqr)
888  {
889  SpecialIntersection(mid + sqrtDiscr, true, result);
890  }
891  else if (discr == rsqr)
892  {
893  SpecialIntersection(mid + sqrtDiscr, false, result);
894  }
895  }
896 
897  // s = -1:
898  if (r > mZero)
899  {
900  SpecialIntersection(mid - sqrtDiscr, true, result);
901  }
902  else
903  {
904  Real rsqr = r * r;
905  if (discr > rsqr)
906  {
907  SpecialIntersection(mid - sqrtDiscr, true, result);
908  }
909  else if (discr == rsqr)
910  {
911  SpecialIntersection(mid - sqrtDiscr, false, result);
912  }
913  }
914  }
915  else if (g[1] < mZero)
916  {
917  // We need s*sqrt(discr) >= -g[0]/g[1] + f1/2.
918  Real r = -g[0] / g[1] - mid;
919 
920  // s = -1:
921  if (r <= mZero)
922  {
923  Real rsqr = r * r;
924  if (discr < rsqr)
925  {
926  SpecialIntersection(mid - sqrtDiscr, true, result);
927  }
928  else
929  {
930  SpecialIntersection(mid - sqrtDiscr, false, result);
931  }
932  }
933 
934  // s = +1:
935  if (r < mZero)
936  {
937  SpecialIntersection(mid + sqrtDiscr, true, result);
938  }
939  else
940  {
941  Real rsqr = r * r;
942  if (discr > rsqr)
943  {
944  SpecialIntersection(mid + sqrtDiscr, true, result);
945  }
946  else if (discr == rsqr)
947  {
948  SpecialIntersection(mid + sqrtDiscr, false, result);
949  }
950  }
951  }
952  else // g[1] = 0
953  {
954  // The graphs of c(x) and f(x) are parabolas of the same
955  // shape. One is a vertical translation of the other.
956  if (g[0] < mZero)
957  {
958  // The graph of f(x) is above that of c(x).
959  SpecialIntersection(mid - sqrtDiscr, true, result);
960  SpecialIntersection(mid + sqrtDiscr, true, result);
961  }
962  else if (g[0] == mZero)
963  {
964  // The graphs of c(x) and f(x) are the same parabola.
965  SpecialIntersection(mid - sqrtDiscr, false, result);
966  SpecialIntersection(mid + sqrtDiscr, false, result);
967  }
968  }
969  }
970  else if (discr == mZero)
971  {
972  // The theoretical root of f(x) is x = -f1/2.
973  Real nchat = -(mC[0] + mid * (mC[1] + mid * mC[2]));
974  if (nchat > mZero)
975  {
976  SpecialIntersection(mid, true, result);
977  }
978  else if (nchat == mZero)
979  {
980  SpecialIntersection(mid, false, result);
981  }
982  }
983  }
984  else if (mE[1] != mZero)
985  {
986  Real xhat = -mE[0] / mE[1];
987  Real nchat = -(mC[0] + xhat * (mC[1] + xhat * mC[2]));
988  if (nchat > mZero)
989  {
990  SpecialIntersection(xhat, true, result);
991  }
992  else if (nchat == mZero)
993  {
994  SpecialIntersection(xhat, false, result);
995  }
996  }
997 }
998 
999 template <typename Real>
1000 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::SpecialIntersection(
1001  Real const& x, bool transverse, Result& result)
1002 {
1003  if (transverse)
1004  {
1005  Real translate = mA2Div2 + x * mA4Div2;
1006  Real nc = -(mC[0] + x * (mC[1] + x * mC[2]));
1007  if (nc < mZero)
1008  {
1009  // Clamp to eliminate the rounding error, but duplicate the point
1010  // because we know that it is a transverse intersection.
1011  nc = mZero;
1012  }
1013 
1014  Real w = Function<Real>::Sqrt(nc);
1015  Real y = w - translate;
1016  result.points[result.numPoints] = { x, y };
1017  result.isTransverse[result.numPoints++] = true;
1018  w = -w;
1019  y = w - translate;
1020  result.points[result.numPoints] = { x, y };
1021  result.isTransverse[result.numPoints++] = true;
1022  }
1023  else
1024  {
1025  // The vertical line at the root is tangent to the ellipse.
1026  Real y = -(mA2Div2 + x * mA4Div2); // w = 0
1027  result.points[result.numPoints] = { x, y };
1028  result.isTransverse[result.numPoints++] = false;
1029  }
1030 }
1031 
1032 
1033 
1034 // FIQuery functions for area of intersection of ellipses.
1035 
1036 template <typename Real>
1037 typename FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::AreaResult
1038 FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::AreaOfIntersection(
1039  Ellipse2<Real> const& ellipse0, Ellipse2<Real> const& ellipse1)
1040 {
1041  EllipseInfo E0;
1042  E0.center = ellipse0.center;
1043  E0.axis = ellipse0.axis;
1044  E0.extent = ellipse0.extent;
1045  E0.sqrExtent = ellipse0.extent * ellipse0.extent;
1046  FinishEllipseInfo(E0);
1047 
1048  EllipseInfo E1;
1049  E1.center = ellipse1.center;
1050  E1.axis = ellipse1.axis;
1051  E1.extent = ellipse1.extent;
1052  E1.sqrExtent = ellipse1.extent * ellipse0.extent;
1053  FinishEllipseInfo(E1);
1054 
1055  AreaResult ar;
1056  ar.configuration = 0;
1057  ar.findResult = operator()(ellipse0, ellipse1);
1058  ar.area = mZero;
1059  AreaDispatch(E0, E1, ar);
1060  return ar;
1061 }
1062 
1063 template <typename Real>
1064 typename FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::AreaResult
1065 FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::AreaOfIntersection(
1066  Vector2<Real> const& center0, Vector2<Real> const axis0[2],
1067  Vector2<Real> const& sqrExtent0, Vector2<Real> const& center1,
1068  Vector2<Real> const axis1[2], Vector2<Real> const& sqrExtent1)
1069 {
1070  EllipseInfo E0;
1071  E0.center = center0;
1072  E0.axis = { axis0[0], axis0[1] };
1073  E0.extent =
1074  {
1075  Function<Real>::Sqrt(sqrExtent0[0]),
1076  Function<Real>::Sqrt(sqrExtent0[1])
1077  };
1078  E0.sqrExtent = sqrExtent0;
1079  FinishEllipseInfo(E0);
1080 
1081  EllipseInfo E1;
1082  E1.center = center1;
1083  E1.axis = { axis1[0], axis1[1] };
1084  E1.extent =
1085  {
1086  Function<Real>::Sqrt(sqrExtent1[0]),
1087  Function<Real>::Sqrt(sqrExtent1[1])
1088  };
1089  E1.sqrExtent = sqrExtent1;
1090  FinishEllipseInfo(E1);
1091 
1092  AreaResult ar;
1093  ar.configuration = 0;
1094  ar.findResult = operator()(center0, axis0, sqrExtent0, center1, axis1,
1095  sqrExtent1);
1096  ar.area = mZero;
1097  AreaDispatch(E0, E1, ar);
1098  return ar;
1099 }
1100 
1101 template <typename Real>
1102 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::FinishEllipseInfo(
1103  EllipseInfo& E)
1104 {
1105  E.M = OuterProduct(E.axis[0], E.axis[0]) /
1106  (E.sqrExtent[0] * Dot(E.axis[0], E.axis[0]));
1107  E.M += OuterProduct(E.axis[1], E.axis[1]) /
1108  (E.sqrExtent[1] * Dot(E.axis[1], E.axis[1]));
1109  E.AB = E.extent[0] * E.extent[1];
1110  E.halfAB = E.AB / mTwo;
1111  E.BpA = E.extent[1] + E.extent[0];
1112  E.BmA = E.extent[1] - E.extent[0];
1113 }
1114 
1115 template <typename Real>
1116 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::AreaDispatch(
1117  EllipseInfo const& E0, EllipseInfo const& E1, AreaResult& ar)
1118 {
1119  if (ar.findResult.intersect)
1120  {
1121  if (ar.findResult.numPoints == 1)
1122  {
1123  // Containment or separation.
1124  AreaCS(E0, E1, ar);
1125  }
1126  else if (ar.findResult.numPoints == 2)
1127  {
1128  if (ar.findResult.isTransverse[0])
1129  {
1130  // Both intersection points are transverse.
1131  Area2(E0, E1, 0, 1, ar);
1132  }
1133  else
1134  {
1135  // Both intersection points are tangential, so one ellipse
1136  // is contained in the other.
1137  AreaCS(E0, E1, ar);
1138  }
1139  }
1140  else if (ar.findResult.numPoints == 3)
1141  {
1142  // The tangential intersection is irrelevant in the area
1143  // computation.
1144  if (!ar.findResult.isTransverse[0])
1145  {
1146  Area2(E0, E1, 1, 2, ar);
1147  }
1148  else if (!ar.findResult.isTransverse[1])
1149  {
1150  Area2(E0, E1, 2, 0, ar);
1151  }
1152  else // ar.findResult.isTransverse[2] == false
1153  {
1154  Area2(E0, E1, 0, 1, ar);
1155  }
1156  }
1157  else // ar.findResult.numPoints == 4
1158  {
1159  Area4(E0, E1, ar);
1160  }
1161  }
1162  else
1163  {
1164  // Containment, separation, or same ellipse.
1165  AreaCS(E0, E1, ar);
1166  }
1167 }
1168 
1169 template <typename Real>
1170 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::AreaCS(
1171  EllipseInfo const& E0, EllipseInfo const& E1, AreaResult& ar)
1172 {
1173  if (ar.findResult.numPoints <= 1)
1174  {
1175  Vector2<Real> diff = E0.center - E1.center;
1176  Real qform0 = Dot(diff, E0.M * diff);
1177  Real qform1 = Dot(diff, E1.M * diff);
1178  if (qform0 > mOne && qform1 > mOne)
1179  {
1180  // Each ellipse center is outside the other ellipse, so the
1181  // ellipses are separated (numPoints == 0) or outside each
1182  // other and just touching (numPoints == 1).
1183  ar.configuration = AreaResult::ELLIPSES_ARE_SEPARATED;
1184  ar.area = mZero;
1185  }
1186  else
1187  {
1188  // One ellipse is inside the other. Determine this indirectly by
1189  // comparing areas.
1190  if (E0.AB < E1.AB)
1191  {
1192  ar.configuration = AreaResult::E1_CONTAINS_E0;
1193  ar.area = mPi * E0.AB;
1194  }
1195  else
1196  {
1197  ar.configuration = AreaResult::E0_CONTAINS_E1;
1198  ar.area = mPi * E1.AB;
1199  }
1200  }
1201  }
1202  else
1203  {
1204  ar.configuration = AreaResult::ELLIPSES_ARE_EQUAL;
1205  ar.area = mPi * E0.AB;
1206  }
1207 }
1208 
1209 template <typename Real>
1210 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::Area2(
1211  EllipseInfo const& E0, EllipseInfo const& E1, int i0, int i1,
1212  AreaResult& ar)
1213 {
1214  ar.configuration = AreaResult::ONE_CHORD_REGION;
1215 
1216  // The endpoints of the chord.
1217  Vector2<Real> const& P0 = ar.findResult.points[i0];
1218  Vector2<Real> const& P1 = ar.findResult.points[i1];
1219 
1220  // Compute locations relative to the ellipses.
1221  Vector2<Real> P0mC0 = P0 - E0.center, P0mC1 = P0 - E1.center;
1222  Vector2<Real> P1mC0 = P1 - E0.center, P1mC1 = P1 - E1.center;
1223 
1224  // Compute the ellipse normal vectors at endpoint P0. This is sufficient
1225  // information to determine chord endpoint order.
1226  Vector2<Real> N0 = E0.M * P0mC0, N1 = E1.M * P0mC1;
1227  Real dotperp = DotPerp(N1, N0);
1228 
1229  // Choose the endpoint order for the chord region associated with E0.
1230  if (dotperp > mZero)
1231  {
1232  // The chord order for E0 is <P0,P1> and for E1 is <P1,P0>.
1233  ar.area =
1234  ComputeAreaChordRegion(E0, P0mC0, P1mC0) +
1235  ComputeAreaChordRegion(E1, P1mC1, P0mC1);
1236  }
1237  else
1238  {
1239  // The chord order for E0 is <P1,P0> and for E1 is <P0,P1>.
1240  ar.area =
1241  ComputeAreaChordRegion(E0, P1mC0, P0mC0) +
1242  ComputeAreaChordRegion(E1, P0mC1, P1mC1);
1243  }
1244 }
1245 
1246 template <typename Real>
1247 void FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::Area4(
1248  EllipseInfo const& E0, EllipseInfo const& E1, AreaResult& ar)
1249 {
1250  ar.configuration = AreaResult::FOUR_CHORD_REGION;
1251 
1252  // Select a counterclockwise ordering of the points of intersection. Use
1253  // the polar coordinates for E0 to do this. The multimap is used in the
1254  // event that computing the intersections involved numerical rounding
1255  // errors that lead to a duplicate intersection, even though the
1256  // intersections are all labeled as transverse. [See the comment in the
1257  // function SpecialIntersection.]
1258  std::multimap<Real, int> ordering;
1259  int i;
1260  for (i = 0; i < 4; ++i)
1261  {
1262  Vector2<Real> PmC = ar.findResult.points[i] - E0.center;
1263  Real x = Dot(E0.axis[0], PmC);
1264  Real y = Dot(E0.axis[1], PmC);
1265  Real theta = Function<Real>::ATan2(y, x);
1266  ordering.insert(std::make_pair(theta, i));
1267  }
1268 
1269  std::array<int, 4> permute;
1270  i = 0;
1271  for (auto const& element : ordering)
1272  {
1273  permute[i++] = element.second;
1274  }
1275 
1276  // Start with the area of the convex quadrilateral.
1277  Vector2<Real> diag20 =
1278  ar.findResult.points[permute[2]] - ar.findResult.points[permute[0]];
1279  Vector2<Real> diag31 =
1280  ar.findResult.points[permute[3]] - ar.findResult.points[permute[1]];
1281  ar.area = Function<Real>::FAbs(DotPerp(diag20, diag31)) / mTwo;
1282 
1283  // Visit each pair of consecutive points. The selection of ellipse for
1284  // the chord-region area calculation uses the "most counterclockwise"
1285  // tangent vector.
1286  for (int i0 = 3, i1 = 0; i1 < 4; i0 = i1++)
1287  {
1288  // Get a pair of consecutive points.
1289  Vector2<Real> const& P0 = ar.findResult.points[permute[i0]];
1290  Vector2<Real> const& P1 = ar.findResult.points[permute[i1]];
1291 
1292  // Compute locations relative to the ellipses.
1293  Vector2<Real> P0mC0 = P0 - E0.center, P0mC1 = P0 - E1.center;
1294  Vector2<Real> P1mC0 = P1 - E0.center, P1mC1 = P1 - E1.center;
1295 
1296  // Compute the ellipse normal vectors at endpoint P0.
1297  Vector2<Real> N0 = E0.M * P0mC0, N1 = E1.M * P0mC1;
1298  Real dotperp = DotPerp(N1, N0);
1299  if (dotperp > mZero)
1300  {
1301  // The chord goes with ellipse E0.
1302  ar.area += ComputeAreaChordRegion(E0, P0mC0, P1mC0);
1303  }
1304  else
1305  {
1306  // The chord goes with ellipse E1.
1307  ar.area += ComputeAreaChordRegion(E1, P0mC1, P1mC1);
1308  }
1309  }
1310 }
1311 
1312 template <typename Real>
1313 Real FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::ComputeAreaChordRegion(
1314  EllipseInfo const& E, Vector2<Real> const& P0mC,
1315  Vector2<Real> const& P1mC)
1316 {
1317  // Compute polar coordinates for P0 and P1 on the ellipse.
1318  Real x0 = Dot(E.axis[0], P0mC);
1319  Real y0 = Dot(E.axis[1], P0mC);
1320  Real theta0 = Function<Real>::ATan2(y0, x0);
1321  Real x1 = Dot(E.axis[0], P1mC);
1322  Real y1 = Dot(E.axis[1], P1mC);
1323  Real theta1 = Function<Real>::ATan2(y1, x1);
1324 
1325  // The arc straddles the atan2 discontinuity on the negative x-axis. Wrap
1326  // the second angle to be larger than the first angle.
1327  if (theta1 < theta0)
1328  {
1329  theta1 += mTwoPi;
1330  }
1331 
1332  // Compute the area portion of the sector due to the triangle.
1333  Real triArea = Function<Real>::FAbs(DotPerp(P0mC, P1mC)) / mTwo;
1334 
1335  // Compute the chord region area.
1336  Real dtheta = theta1 - theta0;
1337  Real F0, F1, sectorArea;
1338  if (dtheta <= mPi)
1339  {
1340  // Use the area formula directly.
1341  // area(theta0,theta1) = F(theta1) - F(theta0) - area(triangle)
1342  F0 = ComputeIntegral(E, theta0);
1343  F1 = ComputeIntegral(E, theta1);
1344  sectorArea = F1 - F0;
1345  return sectorArea - triArea;
1346  }
1347  else
1348  {
1349  // The angle of the elliptical sector is larger than pi radians.
1350  // Use the area formula
1351  // area(theta0,theta1) = pi*a*b - area(theta1,theta0)
1352  theta0 += mTwoPi; // ensure theta0 > theta1
1353  F0 = ComputeIntegral(E, theta0);
1354  F1 = ComputeIntegral(E, theta1);
1355  sectorArea = F0 - F1;
1356  return mPi * E.AB - (sectorArea - triArea);
1357  }
1358 }
1359 
1360 template <typename Real>
1361 Real FIQuery<Real, Ellipse2<Real>, Ellipse2<Real>>::ComputeIntegral(
1362  EllipseInfo const& E, Real const& theta)
1363 {
1364  Real twoTheta = mTwo * theta;
1365  Real sn = Function<Real>::Sin(twoTheta);
1366  Real cs = Function<Real>::Cos(twoTheta);
1367  Real arg = E.BmA * sn / (E.BpA + E.BmA * cs);
1368  return E.halfAB * (theta - Function<Real>::ATan(arg));
1369 }
1370 
1371 
1372 }
GLenum GLfloat param
Definition: glcorearb.h:99
static Real Cos(Real const &x)
Definition: GteFunctions.h:487
#define LogAssert(condition, message)
Definition: GteLogger.h:86
Result operator()(Type0 const &primitive0, Type1 const &primitive1)
Vector< N, Real > extent
static Real Sqrt(Real const &x)
Definition: GteFunctions.h:937
GLint GLenum GLint x
Definition: glcorearb.h:404
GLubyte GLubyte GLubyte GLubyte w
Definition: glcorearb.h:852
GMatrix< Real > MultiplyATB(GMatrix< Real > const &A, GMatrix< Real > const &B)
Definition: GteGMatrix.h:737
GLboolean GLboolean g
Definition: glcorearb.h:1217
static Real FAbs(Real const &x)
Definition: GteFunctions.h:643
#define GTE_C_PI
Definition: GteConstants.h:17
GLfixed y1
Definition: glext.h:4952
typedef int(WINAPI *PFNWGLRELEASEPBUFFERDCARBPROC)(HPBUFFERARB hPbuffer
GLint first
Definition: glcorearb.h:400
Real DotPerp(Vector2< Real > const &v0, Vector2< Real > const &v1)
Definition: GteVector2.h:117
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
GLuint GLfloat x0
Definition: glext.h:9013
void SetCol(int c, Vector< NumRows, Real > const &vec)
Definition: GteMatrix.h:362
static Real Sin(Real const &x)
Definition: GteFunctions.h:851
GLfloat GLfloat GLfloat GLfloat h
Definition: glcorearb.h:1997
static Real ATan2(Real const &y, Real const &x)
Definition: GteFunctions.h:383
static Real ATan(Real const &x)
Definition: GteFunctions.h:329
GLuint GLfloat GLfloat GLfloat x1
Definition: glext.h:9013
GLboolean r
Definition: glcorearb.h:1217
GLdouble s
Definition: glext.h:231
GLuint GLfloat GLfloat y0
Definition: glext.h:9013
GLfloat f
Definition: glcorearb.h:1921
Result operator()(Type0 const &primitive0, Type1 const &primitive1)
#define GTE_C_TWO_PI
Definition: GteConstants.h:20
GLuint64EXT * result
Definition: glext.h:10003
GLint y
Definition: glcorearb.h:98
static unsigned int Find(std::function< Real(Real)> const &F, Real t0, Real t1, unsigned int maxIterations, Real &root)
GMatrix< Real > OuterProduct(GVector< Real > const &U, GVector< Real > const &V)
Definition: GteGMatrix.h:815
Vector< N, Real > center
std::array< Vector< N, Real >, N > axis


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