GteIntpQuadraticNonuniform2.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 
13 
14 // Quadratic interpolation of a network of triangles whose vertices are of
15 // the form (x,y,f(x,y)). This code is an implementation of the algorithm
16 // found in
17 //
18 // Zoltan J. Cendes and Steven H. Wong,
19 // C1 quadratic interpolation over arbitrary point sets,
20 // IEEE Computer Graphics & Applications,
21 // pp. 8-16, 1987
22 //
23 // The TriangleMesh interface must support the following:
24 // int GetNumVertices() const;
25 // int GetNumTriangles() const;
26 // Vector2<Real> const* GetVertices() const;
27 // int const* GetIndices() const;
28 // bool GetVertices(int, std::array<Vector2<Real>, 3>&) const;
29 // bool GetIndices(int, std::array<int, 3>&) const;
30 // bool GetAdjacencies(int, std::array<int, 3>&) const;
31 // bool GetBarycentrics(int, Vector2<Real> const&,
32 // std::array<Real, 3>&) const;
33 // int GetContainingTriangle(Vector2<Real> const&) const;
34 
35 namespace gte
36 {
37 
38 template <typename Real, typename TriangleMesh>
40 {
41 public:
42  // Construction.
43  //
44  // The first constructor requires only F and a measure of the rate of
45  // change of the function values relative to changes in the spatial
46  // variables. The df/dx and df/dy values are estimated at the sample
47  // points using mesh normals and spatialDelta.
48  //
49  // The second constructor requires you to specify function values F and
50  // first-order partial derivative values df/dx and df/dy.
51 
52  IntpQuadraticNonuniform2(TriangleMesh const& mesh, Real const* F,
53  Real spatialDelta);
54 
55  IntpQuadraticNonuniform2(TriangleMesh const& mesh, Real const* F,
56  Real const* FX, Real const* FY);
57 
58  // Quadratic interpolation. The return value is 'true' if and only if the
59  // input point is in the convex hull of the input vertices, in which case
60  // the interpolation is valid.
61  bool operator()(Vector2<Real> const & P, Real& F, Real& FX, Real& FY)
62  const;
63 
64 private:
65  void EstimateDerivatives(Real spatialDelta);
66  void ProcessTriangles();
68  void ComputeCoefficients(int t);
69 
71  {
72  public:
75  Real coeff[19];
76  };
77 
78  class Jet
79  {
80  public:
81  Real F, FX, FY;
82  };
83 
84  TriangleMesh const* mMesh;
85  Real const* mF;
86  Real const* mFX;
87  Real const* mFY;
88  std::vector<Real> mFXStorage;
89  std::vector<Real> mFYStorage;
90  std::vector<TriangleData> mTData;
91 };
92 
93 
94 template <typename Real, typename TriangleMesh>
96  TriangleMesh const& mesh, Real const* F, Real spatialDelta)
97  :
98  mMesh(&mesh),
99  mF(F),
100  mFX(nullptr),
101  mFY(nullptr)
102 {
103  EstimateDerivatives(spatialDelta);
105 }
106 
107 template <typename Real, typename TriangleMesh>
109  TriangleMesh const& mesh, Real const* F, Real const* FX, Real const* FY)
110  :
111  mMesh(&mesh),
112  mF(F),
113  mFX(FX),
114  mFY(FY)
115 {
117 }
118 
119 template <typename Real, typename TriangleMesh>
121  Vector2<Real> const& P, Real& F, Real& FX, Real& FY) const
122 {
123  int t = mMesh->GetContainingTriangle(P);
124  if (t == -1)
125  {
126  // The point is outside the triangulation.
127  return false;
128  }
129 
130  // Get the vertices of the triangle.
131  std::array<Vector2<Real>, 3> V;
132  mMesh->GetVertices(t, V);
133 
134  // Get the additional information for the triangle.
135  TriangleData const& tData = mTData[t];
136 
137  // Determine which of the six subtriangles contains the target point.
138  // Theoretically, P must be in one of these subtriangles.
139  Vector2<Real> sub0 = tData.center;
140  Vector2<Real> sub1;
141  Vector2<Real> sub2 = tData.intersect[2];
142  Vector3<Real> bary;
143  int index;
144 
145  Real const zero = (Real)0, one = (Real)1;
146  AlignedBox3<Real> barybox({ zero, zero, zero }, { one, one, one });
148  int minIndex = 0;
149  Real minDistance = (Real)-1;
150  Vector3<Real> minBary;
151  Vector2<Real> minSub0, minSub1, minSub2;
152 
153  for (index = 1; index <= 6; ++index)
154  {
155  sub1 = sub2;
156  if (index % 2)
157  {
158  sub2 = V[index / 2];
159  }
160  else
161  {
162  sub2 = tData.intersect[index / 2 - 1];
163  }
164 
165  bool valid = ComputeBarycentrics(P, sub0, sub1, sub2, &bary[0]);
166  if (valid
167  && zero <= bary[0] && bary[0] <= one
168  && zero <= bary[1] && bary[1] <= one
169  && zero <= bary[2] && bary[2] <= one)
170  {
171  // P is in triangle <Sub0,Sub1,Sub2>
172  break;
173  }
174 
175  // When computing with floating-point arithmetic, rounding errors
176  // can cause us to reach this code when, theoretically, the point
177  // is in the subtriangle. Keep track of the (b0,b1,b2) that is
178  // closest to the barycentric cube [0,1]^3 and choose the triangle
179  // corresponding to it when all 6 tests previously fail.
180  Real distance = pbQuery(bary, barybox).distance;
181  if (minIndex == 0 || distance < minDistance)
182  {
183  minDistance = distance;
184  minIndex = index;
185  minBary = bary;
186  minSub0 = sub0;
187  minSub1 = sub1;
188  minSub2 = sub2;
189  }
190  }
191 
192  // If the subtriangle was not found, rounding errors caused problems.
193  // Choose the barycentric point closest to the box.
194  if (index > 6)
195  {
196  index = minIndex;
197  bary = minBary;
198  sub0 = minSub0;
199  sub1 = minSub1;
200  sub2 = minSub2;
201  }
202 
203  // Fetch Bezier control points.
204  Real bez[6] =
205  {
206  tData.coeff[0],
207  tData.coeff[12 + index],
208  tData.coeff[13 + (index % 6)],
209  tData.coeff[index],
210  tData.coeff[6 + index],
211  tData.coeff[1 + (index % 6)]
212  };
213 
214  // Evaluate Bezier quadratic.
215  F = bary[0] * (bez[0] * bary[0] + bez[1] * bary[1] + bez[2] * bary[2]) +
216  bary[1] * (bez[1] * bary[0] + bez[3] * bary[1] + bez[4] * bary[2]) +
217  bary[2] * (bez[2] * bary[0] + bez[4] * bary[1] + bez[5] * bary[2]);
218 
219  // Evaluate barycentric derivatives of F.
220  Real FU = ((Real)2)*(bez[0] * bary[0] + bez[1] * bary[1] +
221  bez[2] * bary[2]);
222  Real FV = ((Real)2)*(bez[1] * bary[0] + bez[3] * bary[1] +
223  bez[4] * bary[2]);
224  Real FW = ((Real)2)*(bez[2] * bary[0] + bez[4] * bary[1] +
225  bez[5] * bary[2]);
226  Real duw = FU - FW;
227  Real dvw = FV - FW;
228 
229  // Convert back to (x,y) coordinates.
230  Real m00 = sub0[0] - sub2[0];
231  Real m10 = sub0[1] - sub2[1];
232  Real m01 = sub1[0] - sub2[0];
233  Real m11 = sub1[1] - sub2[1];
234  Real inv = ((Real)1) / (m00*m11 - m10*m01);
235 
236  FX = inv*(m11*duw - m10*dvw);
237  FY = inv*(m00*dvw - m01*duw);
238  return true;
239 }
240 
241 template <typename Real, typename TriangleMesh>
243  Real spatialDelta)
244 {
245  int numVertices = mMesh->GetNumVertices();
246  Vector2<Real> const* vertices = mMesh->GetVertices();
247  int numTriangles = mMesh->GetNumTriangles();
248  int const* indices = mMesh->GetIndices();
249 
250  mFXStorage.resize(numVertices);
251  mFYStorage.resize(numVertices);
252  std::vector<Real> FZ(numVertices);
253  std::fill(mFXStorage.begin(), mFXStorage.end(), (Real)0);
254  std::fill(mFYStorage.begin(), mFYStorage.end(), (Real)0);
255  std::fill(FZ.begin(), FZ.end(), (Real)0);
256 
257  mFX = &mFXStorage[0];
258  mFY = &mFYStorage[0];
259 
260  // Accumulate normals at spatial locations (averaging process).
261  for (int t = 0; t < numTriangles; ++t)
262  {
263  // Get three vertices of triangle.
264  int v0 = *indices++;
265  int v1 = *indices++;
266  int v2 = *indices++;
267 
268  // Compute normal vector of triangle (with positive z-component).
269  Real dx1 = vertices[v1][0] - vertices[v0][0];
270  Real dy1 = vertices[v1][1] - vertices[v0][1];
271  Real dz1 = mF[v1] - mF[v0];
272  Real dx2 = vertices[v2][0] - vertices[v0][0];
273  Real dy2 = vertices[v2][1] - vertices[v0][1];
274  Real dz2 = mF[v2] - mF[v0];
275  Real nx = dy1*dz2 - dy2*dz1;
276  Real ny = dz1*dx2 - dz2*dx1;
277  Real nz = dx1*dy2 - dx2*dy1;
278  if (nz < (Real)0)
279  {
280  nx = -nx;
281  ny = -ny;
282  nz = -nz;
283  }
284 
285  mFXStorage[v0] += nx; mFYStorage[v0] += ny; FZ[v0] += nz;
286  mFXStorage[v1] += nx; mFYStorage[v1] += ny; FZ[v1] += nz;
287  mFXStorage[v2] += nx; mFYStorage[v2] += ny; FZ[v2] += nz;
288  }
289 
290  // Scale the normals to form (x,y,-1).
291  for (int i = 0; i < numVertices; ++i)
292  {
293  if (FZ[i] != (Real)0)
294  {
295  Real inv = -spatialDelta / FZ[i];
296  mFXStorage[i] *= inv;
297  mFYStorage[i] *= inv;
298  }
299  else
300  {
301  mFXStorage[i] = (Real)0;
302  mFYStorage[i] = (Real)0;
303  }
304  }
305 }
306 
307 template <typename Real, typename TriangleMesh>
309 {
310  // Add degenerate triangles to boundary triangles so that interpolation
311  // at the boundary can be treated in the same way as interpolation in
312  // the interior.
313 
314  // Compute centers of inscribed circles for triangles.
315  Vector2<Real> const* vertices = mMesh->GetVertices();
316  int numTriangles = mMesh->GetNumTriangles();
317  int const* indices = mMesh->GetIndices();
318  mTData.resize(numTriangles);
319  int t;
320  for (t = 0; t < numTriangles; ++t)
321  {
322  int v0 = *indices++;
323  int v1 = *indices++;
324  int v2 = *indices++;
325  Circle2<Real> circle;
326  Inscribe(vertices[v0], vertices[v1], vertices[v2], circle);
327  mTData[t].center = circle.center;
328  }
329 
330  // Compute cross-edge intersections.
331  for (t = 0; t < numTriangles; ++t)
332  {
334  }
335 
336  // Compute Bezier coefficients.
337  for (t = 0; t < numTriangles; ++t)
338  {
340  }
341 }
342 
343 template <typename Real, typename TriangleMesh>
346 {
347  // Get the vertices of the triangle.
348  std::array<Vector2<Real>, 3> V;
349  mMesh->GetVertices(t, V);
350 
351  // Get the centers of adjacent triangles.
352  TriangleData& tData = mTData[t];
353  std::array<int, 3> adjacencies;
354  mMesh->GetAdjacencies(t, adjacencies);
355  for (int j0 = 2, j1 = 0; j1 < 3; j0 = j1++)
356  {
357  int a = adjacencies[j0];
358  if (a >= 0)
359  {
360  // Get center of adjacent triangle's inscribing circle.
361  Vector2<Real> U = mTData[a].center;
362  Real m00 = V[j0][1] - V[j1][1];
363  Real m01 = V[j1][0] - V[j0][0];
364  Real m10 = tData.center[1] - U[1];
365  Real m11 = U[0] - tData.center[0];
366  Real r0 = m00*V[j0][0] + m01*V[j0][1];
367  Real r1 = m10*tData.center[0] + m11*tData.center[1];
368  Real invDet = ((Real)1) / (m00*m11 - m01*m10);
369  tData.intersect[j0][0] = (m11*r0 - m01*r1)*invDet;
370  tData.intersect[j0][1] = (m00*r1 - m10*r0)*invDet;
371  }
372  else
373  {
374  // No adjacent triangle, use center of edge.
375  tData.intersect[j0] = ((Real)0.5)*(V[j0] + V[j1]);
376  }
377  }
378 }
379 
380 template <typename Real, typename TriangleMesh>
382 {
383  // Get the vertices of the triangle.
384  std::array<Vector2<Real>, 3> V;
385  mMesh->GetVertices(t, V);
386 
387  // Get the additional information for the triangle.
388  TriangleData& tData = mTData[t];
389 
390  // Get the sample data at main triangle vertices.
391  std::array<int, 3> indices;
392  mMesh->GetIndices(t, indices);
393  Jet jet[3];
394  for (int j = 0; j < 3; ++j)
395  {
396  int k = indices[j];
397  jet[j].F = mF[k];
398  jet[j].FX = mFX[k];
399  jet[j].FY = mFY[k];
400  }
401 
402  // Get centers of adjacent triangles.
403  std::array<int, 3> adjacencies;
404  mMesh->GetAdjacencies(t, adjacencies);
405  Vector2<Real> U[3];
406  for (int j0 = 2, j1 = 0; j1 < 3; j0 = j1++)
407  {
408  int a = adjacencies[j0];
409  if (a >= 0)
410  {
411  // Get center of adjacent triangle's circumscribing circle.
412  U[j0] = mTData[a].center;
413  }
414  else
415  {
416  // No adjacent triangle, use center of edge.
417  U[j0] = ((Real)0.5)*(V[j0] + V[j1]);
418  }
419  }
420 
421  // Compute intermediate terms.
422  std::array<Real, 3> cenT, cen0, cen1, cen2;
423  mMesh->GetBarycentrics(t, tData.center, cenT);
424  mMesh->GetBarycentrics(t, U[0], cen0);
425  mMesh->GetBarycentrics(t, U[1], cen1);
426  mMesh->GetBarycentrics(t, U[2], cen2);
427 
428  Real alpha = (cenT[1] * cen1[0] - cenT[0] * cen1[1])
429  / (cen1[0] - cenT[0]);
430  Real beta = (cenT[2] * cen2[1] - cenT[1] * cen2[2])
431  / (cen2[1] - cenT[1]);
432  Real gamma = (cenT[0] * cen0[2] - cenT[2] * cen0[0])
433  / (cen0[2] - cenT[2]);
434  Real oneMinusAlpha = (Real)1 - alpha;
435  Real oneMinusBeta = (Real)1 - beta;
436  Real oneMinusGamma = (Real)1 - gamma;
437 
438  Real tmp, A[9], B[9];
439 
440  tmp = cenT[0] * V[0][0] + cenT[1] * V[1][0] + cenT[2] * V[2][0];
441  A[0] = ((Real)0.5)*(tmp - V[0][0]);
442  A[1] = ((Real)0.5)*(tmp - V[1][0]);
443  A[2] = ((Real)0.5)*(tmp - V[2][0]);
444  A[3] = ((Real)0.5)*beta*(V[2][0] - V[0][0]);
445  A[4] = ((Real)0.5)*oneMinusGamma*(V[1][0] - V[0][0]);
446  A[5] = ((Real)0.5)*gamma*(V[0][0] - V[1][0]);
447  A[6] = ((Real)0.5)*oneMinusAlpha*(V[2][0] - V[1][0]);
448  A[7] = ((Real)0.5)*alpha*(V[1][0] - V[2][0]);
449  A[8] = ((Real)0.5)*oneMinusBeta*(V[0][0] - V[2][0]);
450 
451  tmp = cenT[0] * V[0][1] + cenT[1] * V[1][1] + cenT[2] * V[2][1];
452  B[0] = ((Real)0.5)*(tmp - V[0][1]);
453  B[1] = ((Real)0.5)*(tmp - V[1][1]);
454  B[2] = ((Real)0.5)*(tmp - V[2][1]);
455  B[3] = ((Real)0.5)*beta*(V[2][1] - V[0][1]);
456  B[4] = ((Real)0.5)*oneMinusGamma*(V[1][1] - V[0][1]);
457  B[5] = ((Real)0.5)*gamma*(V[0][1] - V[1][1]);
458  B[6] = ((Real)0.5)*oneMinusAlpha*(V[2][1] - V[1][1]);
459  B[7] = ((Real)0.5)*alpha*(V[1][1] - V[2][1]);
460  B[8] = ((Real)0.5)*oneMinusBeta*(V[0][1] - V[2][1]);
461 
462  // Compute Bezier coefficients.
463  tData.coeff[2] = jet[0].F;
464  tData.coeff[4] = jet[1].F;
465  tData.coeff[6] = jet[2].F;
466 
467  tData.coeff[14] = jet[0].F + A[0] * jet[0].FX + B[0] * jet[0].FY;
468  tData.coeff[7] = jet[0].F + A[3] * jet[0].FX + B[3] * jet[0].FY;
469  tData.coeff[8] = jet[0].F + A[4] * jet[0].FX + B[4] * jet[0].FY;
470  tData.coeff[16] = jet[1].F + A[1] * jet[1].FX + B[1] * jet[1].FY;
471  tData.coeff[9] = jet[1].F + A[5] * jet[1].FX + B[5] * jet[1].FY;
472  tData.coeff[10] = jet[1].F + A[6] * jet[1].FX + B[6] * jet[1].FY;
473  tData.coeff[18] = jet[2].F + A[2] * jet[2].FX + B[2] * jet[2].FY;
474  tData.coeff[11] = jet[2].F + A[7] * jet[2].FX + B[7] * jet[2].FY;
475  tData.coeff[12] = jet[2].F + A[8] * jet[2].FX + B[8] * jet[2].FY;
476 
477  tData.coeff[5] = alpha*tData.coeff[10] + oneMinusAlpha*tData.coeff[11];
478  tData.coeff[17] = alpha*tData.coeff[16] + oneMinusAlpha*tData.coeff[18];
479  tData.coeff[1] = beta*tData.coeff[12] + oneMinusBeta*tData.coeff[7];
480  tData.coeff[13] = beta*tData.coeff[18] + oneMinusBeta*tData.coeff[14];
481  tData.coeff[3] = gamma*tData.coeff[8] + oneMinusGamma*tData.coeff[9];
482  tData.coeff[15] = gamma*tData.coeff[14] + oneMinusGamma*tData.coeff[16];
483  tData.coeff[0] = cenT[0] * tData.coeff[14] + cenT[1] * tData.coeff[16] +
484  cenT[2] * tData.coeff[18];
485 }
486 
487 
488 }
GLfloat GLfloat GLfloat alpha
Definition: glcorearb.h:107
bool Inscribe(Vector2< Real > const &v0, Vector2< Real > const &v1, Vector2< Real > const &v2, Circle2< Real > &circle)
GLfloat GLfloat v1
Definition: glcorearb.h:812
GLfixed GLfixed nz
Definition: glext.h:4889
GLsizei GLsizei GLfloat distance
Definition: glext.h:9704
GLboolean GLboolean GLboolean GLboolean a
Definition: glcorearb.h:1217
GLsizei GLenum const void * indices
Definition: glcorearb.h:401
GLbyte nx
Definition: glext.h:6082
GLfloat v0
Definition: glcorearb.h:811
GLdouble GLdouble t
Definition: glext.h:239
bool ComputeBarycentrics(Vector2< Real > const &p, Vector2< Real > const &v0, Vector2< Real > const &v1, Vector2< Real > const &v2, Real bary[3], Real epsilon=(Real) 0)
Definition: GteVector2.h:135
bool operator()(Vector2< Real > const &P, Real &F, Real &FX, Real &FY) const
GLfloat GLfloat GLfloat v2
Definition: glcorearb.h:813
GLuint index
Definition: glcorearb.h:781
std::vector< TriangleData > mTData
IntpQuadraticNonuniform2(TriangleMesh const &mesh, Real const *F, Real spatialDelta)
GLfixed ny
Definition: glext.h:4889
Vector< N, Real > center


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