GteConstrainedDelaunay2.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 <list>
12 
13 // Various parts of the code have this trap for error conditions. With a
14 // correct algorithm and exact arithmetic, we do not expect to trigger the
15 // error. However, with floating-point arithmetic, it is possible that the
16 // triangulation becomes malformed. The constrained Delaunay triangulation
17 // implementation is designed to return gracefully with such a failure. The
18 // following macros are used to make the code more readable. Do NOT disable
19 // them, because they have necessary side effects.
20 #define GTE_CDT_REQUIRE(c) { if (!(c)) { Trap(); return false; } }
21 #define GTE_CDT_FAILURE { Trap(); return false; }
22 #define GTE_CDT_REQUIRE_RET(c, r) { if (!(c)) { Trap(); return r; } }
23 #define GTE_CDT_FAILURE_RET(r) { Trap(); return r; }
24 
25 namespace gte
26 {
27 
28 template <typename InputType, typename ComputeType>
29 class ConstrainedDelaunay2 : public Delaunay2<InputType, ComputeType>
30 {
31 public:
32  // The class is a functor to support computing the constrained Delaunay
33  // triangulation of multiple data sets using the same class object.
34  virtual ~ConstrainedDelaunay2();
36 
37  // This operator computes the Delaunay triangulation only. Read the
38  // Delaunay2 constructor comments about 'vertices' and 'epsilon'. The
39  // 'edges' array has indices into the 'vertices' array. No two edges
40  // should intersect except at endpoints.
41  bool operator()(int numVertices, Vector2<InputType> const* vertices,
42  InputType epsilon);
43 
44  // Insert required edges into the triangulation. For correctness of the
45  // algorithm, if two edges passed to this function intersect, they must
46  // do so only at vertices passed to operator(). If you have two edges
47  // that intersect at a point not in the vertices, compute that point of
48  // intersection and subdivide the edges at that intersection (to form
49  // more edges), and add the point to the vertices before calling
50  // operator(). This function has an output array that contains the
51  // input edge when the only vertices on the edge are its endpoints. If
52  // the input edge passes through more vertices, the edge is subdivided
53  // in this function. The output edge is that subdivision with first
54  // vertex edge[0] and last vertex edge[1], and the other vertices are
55  // correctly ordered along the edge.
56  bool Insert(std::array<int, 2> const& edge, std::vector<int>& outEdge);
57 
58 private:
59  // The top-level entry point for inserting an edge in the triangulation.
60  bool Insert(std::array<int, 2> const& edge, int v0Triangle,
61  std::vector<int>& outEdge);
62 
63  // Process the coincident edge.
64  bool ProcessCoincident(int tri, int v0, int v1, int vOther,
65  std::vector<int>& outEdge);
66 
67  // Process the triangle strip originating at the first endpoint of the
68  // edge.
69  bool ProcessInterior(int tri, int v0, int v1, int vNext, int vPrev,
70  std::vector<int>& outEdge);
71 
72  // Remove the triangles in the triangle strip and retriangulate the
73  // left and right polygons using the empty circumcircle condition.
74  bool Retriangulate(std::vector<int>& polygon,
75  std::vector<std::array<int, 2>> const& lBoundary,
76  std::vector<std::array<int, 2>> const& rBoundary);
77 
79  std::vector<std::array<int, 2>> const& lBoundary,
80  int i0, int i1, int a0, std::vector<int>& polygon);
81 
83  std::vector<std::array<int, 2>> const& rBoundary,
84  int i0, int i1, int a0, std::vector<int>& polygon);
85 
86  int SelectSplit(std::vector<std::array<int, 2>> const& boundary, int i0,
87  int i1) const;
88 
89  // Compute a pseudosquared distance from the vertex at v2 to the edge
90  // <v0,v1>.
91  ComputeType ComputePSD(int v0, int v1, int v2) const;
92 
93  // Search the triangulation for a triangle that contains the specified
94  // vertex.
95  int GetLinkTriangle(int v) const;
96 
97  // Determine the index in {0,1,2} for the triangle 'tri' that contains
98  // the vertex 'v'.
99  int GetIndexOfVertex(int tri, int v) const;
100 
101  // Given a triangle 'tri' with CCW-edge <v0,v1>, return <adj,v2> where
102  // 'adj' is the index of the triangle adjacent to 'tri' that shares the
103  // edge and 'v2' is the vertex of the adjacent triangle opposite the
104  // edge. This function supports traversing a triangle strip that contains
105  // a constraint edge, so it is called only when an adjacent triangle
106  // actually exists.
107  std::array<int, 2> GetAdjInterior(int tri, int v0, int v1) const;
108 
109  // Given a triangle 'tri' of the triangle strip, the boundary edge must
110  // contain the vertex with index 'needBndVertex'. The input
111  // 'needAdjVIndex' specifies where to look for the index of the triangle
112  // outside the strip but adjacent to the boundary edge. The return
113  // value is <needBndVertex, adj> and is used to connect 'tri' and 'adj'
114  // across a triangle strip boundary.
115  std::array<int, 2> GetAdjBoundary(int tri, int needBndVertex,
116  int needAdjVIndex) const;
117 
118  // Set the indices and adjacencies arrays so that 'tri' and 'adj' share
119  // the common edge; 'tri' has CCW-edge <v0,v1> and 'adj' has CCW-edge
120  // <v1,v0>.
121  bool Connect(int tri, int adj, int v0, int v1);
122 
123  // Create an ordered list of triangles forming the link of a vertex. The
124  // pair of the list is <triangle,GetIndexOfV(triangle)>. This allows us
125  // to cache the index of v relative to each triangle in the link. The
126  // vertex v might be a boundary vertex, in which case the neighborhood is
127  // open; otherwise, v is an interior vertex and the neighborhood is
128  // closed. The 'isOpen' parameter specifies the case.
129  bool BuildLink(int v, int vTriangle, std::list<std::pair<int,int>>& link,
130  bool& isOpen) const;
131 
132  // Support for return-false-on-error. This allows us to investigate the
133  // error by setting a break point, trigger an assert when the logger is
134  // active, and get a call stack.
135  void Trap() const;
136 };
137 
138 
139 template <typename InputType, typename ComputeType>
141 {
142 }
143 
144 template <typename InputType, typename ComputeType>
146  :
147  Delaunay2<InputType, ComputeType>()
148 {
149 }
150 
151 template <typename InputType, typename ComputeType>
153  int numVertices, Vector2<InputType> const* vertices, InputType epsilon)
154 {
156  vertices, epsilon);
157 }
158 
159 template <typename InputType, typename ComputeType>
161  std::array<int, 2> const& edge, std::vector<int>& outEdge)
162 {
163  int v0 = edge[0], v1 = edge[1];
164  if (0 <= v0 && v0 < this->mNumVertices
165  && 0 <= v1 && v1 < this->mNumVertices)
166  {
167  int v0Triangle = GetLinkTriangle(v0);
168  if (v0Triangle >= 0)
169  {
170  // Once an edge is inserted, the base-class mGraph no longer
171  // represents the triangulation. Clear it in case the user tries
172  // to access it.
173  this->mGraph.Clear();
174 
175  outEdge.clear();
176  return Insert(edge, v0Triangle, outEdge);
177  }
178  }
179  return false;
180 }
181 
182 template <typename InputType, typename ComputeType>
184  std::array<int, 2> const& edge, int v0Triangle, std::vector<int>& outEdge)
185 {
186  // Create the neighborhood of triangles that share the vertex v0. On
187  // entry we already know one such triangle (v0Triangle).
188  int v0 = edge[0], v1 = edge[1];
189  std::list<std::pair<int, int>> link;
190  bool isOpen = true;
191  GTE_CDT_REQUIRE(BuildLink(v0, v0Triangle, link, isOpen));
192 
193  // Determine which triangle contains the edge. Process the edge according
194  // to whether it is strictly between two triangle edges or is coincident
195  // with a triangle edge.
196  auto item = link.begin();
197  std::array<int, 3> indices;
198  GTE_CDT_REQUIRE(this->GetIndices(item->first, indices));
199  int vNext = indices[(item->second + 1) % 3];
200  int qr0 = this->mQuery.ToLine(v1, v0, vNext);
201  while (item != link.end())
202  {
203  if (qr0 == 0)
204  {
205  // We have to be careful about parallel edges that point in
206  // the opposite direction of <v0,v1>.
207  Vector2<ComputeType> const& ctv0 = this->mComputeVertices[v0];
208  Vector2<ComputeType> const& ctv1 = this->mComputeVertices[v1];
209  Vector2<ComputeType> const& ctvnext =
210  this->mComputeVertices[vNext];
211  if (Dot(ctv1 - ctv0, ctvnext - ctv0) > (ComputeType)0)
212  {
213  // <v0,v1> is coincident to triangle edge0.
214  return ProcessCoincident(item->first, v0, v1, vNext,
215  outEdge);
216  }
217 
218  // Make sure we enter the next "if" statement to continue
219  // traversing the link.
220  qr0 = 1;
221  }
222 
223  if (qr0 > 0)
224  {
225  // <v0,v1> is not in triangle. Visit the next triangle.
226  if (++item == link.end())
227  {
228  return false;
229  }
230  GTE_CDT_REQUIRE(this->GetIndices(item->first, indices));
231  vNext = indices[(item->second + 1) % 3];
232  qr0 = this->mQuery.ToLine(v1, v0, vNext);
233  continue;
234  }
235 
236  int vPrev = indices[(item->second + 2) % 3];
237  int qr1 = this->mQuery.ToLine(v1, v0, vPrev);
238  while (item != link.end())
239  {
240  if (qr1 == 0)
241  {
242  // We have to be careful about parallel edges that point in
243  // the opposite direction of <v0,v1>.
244  Vector2<ComputeType> const& ctv0 = this->mComputeVertices[v0];
245  Vector2<ComputeType> const& ctv1 = this->mComputeVertices[v1];
246  Vector2<ComputeType> const& ctvprev =
247  this->mComputeVertices[vPrev];
248  if (Dot(ctv1 - ctv0, ctvprev - ctv0) > (ComputeType)0)
249  {
250  // <v0,v1> is coincident to triangle edge1.
251  return ProcessCoincident(item->first, v0, v1, vPrev,
252  outEdge);
253  }
254 
255  // Make sure we enter the next "if" statement to continue
256  // traversing the link.
257  qr1 = -1;
258  }
259 
260  if (qr1 < 0)
261  {
262  // <v0,v1> is not in triangle. Visit the next triangle.
263  if (++item == link.end())
264  {
265  return false;
266  }
267  this->GetIndices(item->first, indices);
268  vNext = vPrev;
269  vPrev = indices[(item->second + 2) % 3];
270  qr1 = this->mQuery.ToLine(v1, v0, vPrev);
271  continue;
272  }
273 
274  // <v0,v1> is interior to triangle <v0,vNext,vPrev>.
275  return ProcessInterior(item->first, v0, v1, vNext, vPrev,
276  outEdge);
277  }
278  break;
279  }
280 
281  // The edge must be contained in some link triangle.
283 }
284 
285 template <typename InputType, typename ComputeType>
287  int v0, int v1, int vOther, std::vector<int>& outEdge)
288 {
289  outEdge.push_back(v0);
290  if (v1 != vOther)
291  {
292  // Decompose the edge and process the right-most subedge.
293  return Insert({ vOther, v1 }, tri, outEdge);
294  }
295  else
296  {
297  // <v0,v1> is already in the triangulation.
298  outEdge.push_back(v1);
299  return true;
300  }
301 }
302 
303 template <typename InputType, typename ComputeType>
305  int v0, int v1, int vNext, int vPrev, std::vector<int>& outEdge)
306 {
307  // The triangles of the strip are stored in 'polygon'. The
308  // retriangulation leads to the same number of triangles, so we can reuse
309  // the mIndices[] and mAdjacencies[] locations implied by the 'polygons'
310  // indices.
311  std::vector<int> polygon;
312 
313  // The sBoundary[i] (s in {l,r}) array element is <v0,adj>; see the
314  // header comments for GetAdjBoundary about what these mean. The
315  // boundary vertex is 'v0', the adjacent triangle 'adj' is outside the
316  // strip and shares the edge <sBoundary[i-1][0], sBoundary[i][0]> with a
317  // triangle in 'polygon'. This information allows us to connect the
318  // adjacent triangles outside the strip to new triangles inserted by
319  // the retriangulation. The value sBoundary[0][1,2] values are set to
320  // -1 but they are not used in the construction.
321  std::vector<std::array<int, 2>> lBoundary, rBoundary;
322  std::array<int, 2> binfo;
323 
324  polygon.push_back(tri);
325 
326  lBoundary.push_back({ v0, -1 });
327  binfo = GetAdjBoundary(tri, vPrev, vPrev);
328  GTE_CDT_REQUIRE(binfo[0] != -2);
329  lBoundary.push_back(binfo);
330 
331  rBoundary.push_back({ v0, -1 });
332  binfo = GetAdjBoundary(tri, vNext, v0);
333  GTE_CDT_REQUIRE(binfo[0] != -2);
334  rBoundary.push_back(binfo);
335 
336  // Visit the triangles in the strip. Guard against an infinite loop.
337  for (int i = 0; i < this->mNumTriangles; ++i)
338  {
339  // Find the vertex of the adjacent triangle that is opposite the
340  // edge <vNext,vPrev> shared with the current triangle.
341  auto iinfo = GetAdjInterior(tri, vNext, vPrev);
342  int adj = iinfo[0], vOpposite = iinfo[1];
343  GTE_CDT_REQUIRE(vOpposite >= 0);
344 
345  // Visit the adjacent triangle and insert it into the polygon.
346  tri = adj;
347  polygon.push_back(tri);
348 
349  int qr = this->mQuery.ToLine(vOpposite, v0, v1);
350  if (qr == 0)
351  {
352  // We have encountered a vertex that terminates the triangle
353  // strip. Retriangulate the polygon. If the edge continues
354  // through vOpposite, decompose the edge and insert the
355  // right-most subedge.
356  binfo = GetAdjBoundary(tri, vOpposite, vOpposite);
357  GTE_CDT_REQUIRE(binfo[0] != -2);
358  lBoundary.push_back(binfo);
359 
360  binfo = GetAdjBoundary(tri, vOpposite, vNext);
361  GTE_CDT_REQUIRE(binfo[0] != -2);
362  rBoundary.push_back(binfo);
363 
364  Retriangulate(polygon, lBoundary, rBoundary);
365  if (vOpposite != v1)
366  {
367  outEdge.push_back(v0);
368  return Insert({ vOpposite, v1 }, tri, outEdge);
369  }
370  else
371  {
372  return true;
373  }
374  }
375 
376  if (qr < 0)
377  {
378  binfo = GetAdjBoundary(tri, vOpposite, vOpposite);
379  GTE_CDT_REQUIRE(binfo[0] != -2);
380  lBoundary.push_back(binfo);
381  vPrev = vOpposite;
382  }
383  else // qr > 0
384  {
385  binfo = GetAdjBoundary(tri, vOpposite, vNext);
386  GTE_CDT_REQUIRE(binfo[0] != -2);
387  rBoundary.push_back(binfo);
388  vNext = vOpposite;
389  }
390  }
391 
392  // The triangle strip should have been located in the loop.
394 }
395 
396 template <typename InputType, typename ComputeType>
398  std::vector<int>& polygon,
399  std::vector<std::array<int, 2>> const& lBoundary,
400  std::vector<std::array<int, 2>> const& rBoundary)
401 {
402  int t0 = RetriangulateLRecurse(lBoundary, 0,
403  static_cast<int>(lBoundary.size()) - 1, -1, polygon);
404 
405  int t1 = RetriangulateRRecurse(rBoundary, 0,
406  static_cast<int>(rBoundary.size()) - 1, -1, polygon);
407 
408  int v0 = lBoundary.front()[0];
409  int v1 = lBoundary.back()[0];
410  GTE_CDT_REQUIRE(Connect(t0, t1, v0, v1));
411  return true;
412 }
413 
414 template <typename InputType, typename ComputeType>
416  std::vector<std::array<int, 2>> const& lBoundary, int i0, int i1, int a0,
417  std::vector<int>& polygon)
418 {
419  // Create triangles when recursing down, connect adjacent triangles when
420  // returning.
421 
422  int v0 = lBoundary[i0][0];
423  int v1 = lBoundary[i1][0];
424 
425  if (i1 - i0 == 1)
426  {
427  GTE_CDT_REQUIRE_RET(Connect(a0, lBoundary[i1][1], v1, v0), -2);
428  return -1; // No triangle created.
429  }
430  else
431  {
432  // Select i2 in [i0+1,i1-1] for minimum distance to edge <i0,i1>.
433  int i2 = SelectSplit(lBoundary, i0, i1);
434  int v2 = lBoundary[i2][0];
435 
436  // Reuse a triangle and fill in its new vertices.
437  int tri = polygon.back();
438  polygon.pop_back();
439  this->mIndices[3 * tri + 0] = v0;
440  this->mIndices[3 * tri + 1] = v1;
441  this->mIndices[3 * tri + 2] = v2;
442 
443  // Recurse downward and create triangles.
444  int ret0 = RetriangulateLRecurse(lBoundary, i0, i2, tri, polygon);
445  GTE_CDT_REQUIRE_RET(ret0 >= -1, -2);
446  int ret1 = RetriangulateLRecurse(lBoundary, i2, i1, tri, polygon);
447  GTE_CDT_REQUIRE_RET(ret1 >= -1, -2);
448 
449  // Return and connect triangles.
450  GTE_CDT_REQUIRE_RET(Connect(a0, tri, v1, v0), -2);
451  return tri;
452  }
453 }
454 
455 template <typename InputType, typename ComputeType>
457  std::vector<std::array<int, 2>> const& rBoundary, int i0, int i1, int a0,
458  std::vector<int>& polygon)
459 {
460  // Create triangles when recursing down, connect adjacent triangles when
461  // returning.
462 
463  int v0 = rBoundary[i0][0];
464  int v1 = rBoundary[i1][0];
465 
466  if (i1 - i0 == 1)
467  {
468  GTE_CDT_REQUIRE_RET(Connect(a0, rBoundary[i1][1], v0, v1), -2);
469  return -1; // No triangle created.
470  }
471  else
472  {
473  // Select i2 in [i0+1,i1-1] for minimum distance to edge <i0,i1>.
474  int i2 = SelectSplit(rBoundary, i0, i1);
475  int v2 = rBoundary[i2][0];
476 
477  // Reuse a triangle and fill in its new vertices.
478  int tri = polygon.back();
479  polygon.pop_back();
480  this->mIndices[3 * tri + 0] = v1;
481  this->mIndices[3 * tri + 1] = v0;
482  this->mIndices[3 * tri + 2] = v2;
483 
484  // Recurse downward and create triangles.
485  int ret0 = RetriangulateRRecurse(rBoundary, i0, i2, tri, polygon);
486  GTE_CDT_REQUIRE_RET(ret0 >= -1, -2);
487  int ret1 = RetriangulateRRecurse(rBoundary, i2, i1, tri, polygon);
488  GTE_CDT_REQUIRE_RET(ret1 >= -1, -2);
489 
490  // Return and connect triangles.
491  GTE_CDT_REQUIRE_RET(Connect(a0, tri, v0, v1), -2);
492  return tri;
493  }
494 }
495 
496 template <typename InputType, typename ComputeType>
498  std::vector<std::array<int, 2>> const& boundary, int i0, int i1) const
499 {
500  int i2;
501  if (i1 - i0 == 2)
502  {
503  // This is the only candidate.
504  i2 = i0 + 1;
505  }
506  else // i1 - i0 > 2
507  {
508  // Select the index i2 in [i0+1,i1-1] for which the distance from the
509  // vertex v2 at i2 to the edge <v0,v1> is minimized. To allow exact
510  // arithmetic, use a pseudosquared distance that avoids divisions and
511  // square roots.
512  i2 = i0 + 1;
513  int v0 = boundary[i0][0];
514  int v1 = boundary[i1][0];
515  int v2 = boundary[i2][0];
516  ComputeType minpsd = ComputePSD(v0, v1, v2);
517  for (int i = i2 + 1; i < i1; ++i)
518  {
519  v2 = boundary[i][0];
520  ComputeType psd = ComputePSD(v0, v1, v2);
521  if (psd < minpsd)
522  {
523  minpsd = psd;
524  i2 = i;
525  }
526  }
527  }
528  return i2;
529 }
530 
531 template <typename InputType, typename ComputeType>
533  int v1, int v2) const
534 {
535  ComputeType psd;
536 
537  Vector2<ComputeType> const& ctv0 = this->mComputeVertices[v0];
538  Vector2<ComputeType> const& ctv1 = this->mComputeVertices[v1];
539  Vector2<ComputeType> const& ctv2 = this->mComputeVertices[v2];
540 
541  Vector2<ComputeType> V1mV0 = ctv1 - ctv0;
542  Vector2<ComputeType> V2mV0 = ctv2 - ctv0;
543  ComputeType sqrlen10 = Dot(V1mV0, V1mV0);
544  ComputeType dot = Dot(V1mV0, V2mV0);
545  ComputeType zero(0);
546 
547  if (dot <= zero)
548  {
549  ComputeType sqrlen20 = Dot(V2mV0, V2mV0);
550  psd = sqrlen10 * sqrlen20;
551  }
552  else
553  {
554  Vector2<ComputeType> V2mV1 = ctv2 - ctv1;
555  dot = Dot(V1mV0, V2mV1);
556  if (dot >= zero)
557  {
558  ComputeType sqrlen21 = Dot(V2mV1, V2mV1);
559  psd = sqrlen10 * sqrlen21;
560  }
561  else
562  {
563  dot = DotPerp(V2mV0, V1mV0);
564  psd = sqrlen10 * dot * dot;
565  }
566  }
567 
568  return psd;
569 }
570 
571 template <typename InputType, typename ComputeType>
573 {
574  // Remap in case an edge vertex was specified that is a duplicate.
575  v = this->mDuplicates[v];
576 
577  int tri = 0;
578  for (int i = 0; i < this->mNumTriangles; ++i)
579  {
580  // Test whether v is a vertex of the triangle.
581  std::array<int, 3> indices;
582  GTE_CDT_REQUIRE(this->GetIndices(tri, indices));
583  for (int j = 0; j < 3; ++j)
584  {
585  if (v == indices[j])
586  {
587  return tri;
588  }
589  }
590 
591  // v must be outside the triangle.
592  for (int j0 = 2, j1 = 0; j1 < 3; j0 = j1++)
593  {
594  if (this->mQuery.ToLine(v, indices[j0], indices[j1]) > 0)
595  {
596  // Vertex v sees the edge from outside, so traverse to the
597  // triangle sharing the edge.
598  std::array<int, 3> adjacencies;
599  GTE_CDT_REQUIRE(this->GetAdjacencies(tri, adjacencies));
600  int adj = adjacencies[j0];
601  GTE_CDT_REQUIRE_RET(adj >= 0, -1);
602  tri = adj;
603  break;
604  }
605  }
606  }
607 
608  // The vertex must be in the triangulation.
610 }
611 
612 template <typename InputType, typename ComputeType>
614  int v) const
615 {
616  std::array<int, 3> indices;
617  GTE_CDT_REQUIRE_RET(this->GetIndices(tri, indices), -1);
618  int indexOfV;
619  for (indexOfV = 0; indexOfV < 3; ++indexOfV)
620  {
621  if (v == indices[indexOfV])
622  {
623  return indexOfV;
624  }
625  }
626 
627  // Unexpected failure.
629 }
630 
631 template <typename InputType, typename ComputeType>
633 GetAdjInterior(int tri, int v0, int v1) const
634 {
635  std::array<int, 2> error = { -2, -2 };
636  int vIndex = GetIndexOfVertex(tri, v0);
637  GTE_CDT_REQUIRE_RET(vIndex >= 0, error);
638  int adj = this->mAdjacencies[3 * tri + vIndex];
639  if (adj >= 0)
640  {
641  for (int v2Index = 0; v2Index < 3; ++v2Index)
642  {
643  int v2 = this->mIndices[3 * adj + v2Index];
644  if (v2 != v0 && v2 != v1)
645  {
646  return{ adj, v2 };
647  }
648  }
649  }
650  else
651  {
652  return{ -1, -1 };
653  }
654 
655  GTE_CDT_FAILURE_RET(error);
656 }
657 
658 template <typename InputType, typename ComputeType>
660 GetAdjBoundary(int tri, int needBndVertex, int needAdjVIndex) const
661 {
662  std::array<int, 2> error = { -2, -2 };
663  int vIndex = GetIndexOfVertex(tri, needAdjVIndex);
664  GTE_CDT_REQUIRE_RET(vIndex >= 0, error);
665  int adj = this->mAdjacencies[3 * tri + vIndex];
666  return{ needBndVertex, adj };
667 }
668 
669 template <typename InputType, typename ComputeType>
671  int v0, int v1)
672 {
673  if (tri >= 0)
674  {
675  int v0Index = GetIndexOfVertex(tri, v0);
676  GTE_CDT_REQUIRE(v0Index >= 0);
677  if (adj >= 0)
678  {
679  int v1Index = GetIndexOfVertex(adj, v1);
680  GTE_CDT_REQUIRE(v1Index >= 0);
681  this->mAdjacencies[3 * adj + v1Index] = tri;
682  }
683 
684  this->mAdjacencies[3 * tri + v0Index] = adj;
685  }
686  // else: tri = -1, which occurs in the top-level call to retriangulate
687  return true;
688 }
689 
690 template <typename InputType, typename ComputeType>
692  int vTriangle, std::list<std::pair<int, int>>& link, bool& isOpen) const
693 {
694  // The list starts with a known triangle in the link of v.
695  int vStartIndex = GetIndexOfVertex(vTriangle, v);
696  GTE_CDT_REQUIRE(vStartIndex >= 0);
697  link.push_front(std::make_pair(vTriangle, vStartIndex));
698 
699  // Traverse adjacent triangles to the "left" of v. Guard against an
700  // infinite loop.
701  int tri = vTriangle, vIndex = vStartIndex;
702  std::array<int, 3> adjacencies;
703  for (int i = 0; i < this->mNumTriangles; ++i)
704  {
705  GTE_CDT_REQUIRE(this->GetAdjacencies(tri, adjacencies));
706  int adjPrev = adjacencies[(vIndex + 2) % 3];
707  if (adjPrev >= 0)
708  {
709  if (adjPrev != vTriangle)
710  {
711  tri = adjPrev;
712  vIndex = GetIndexOfVertex(tri, v);
713  GTE_CDT_REQUIRE(vIndex >= 0);
714  link.push_back(std::make_pair(tri, vIndex));
715  }
716  else
717  {
718  // We have reached the starting triangle, so v is an interior
719  // vertex.
720  isOpen = false;
721  return true;
722  }
723  }
724  else
725  {
726  // We have reached a triangle with boundary edge, so v is a
727  // boundary vertex. We mush find more triangles by searching
728  // to the "right" of v. Guard against an infinite loop.
729  isOpen = true;
730  tri = vTriangle;
731  vIndex = vStartIndex;
732  for (int j = 0; j < this->mNumTriangles; ++j)
733  {
734  this->GetAdjacencies(tri, adjacencies);
735  int adjNext = adjacencies[vIndex];
736  if (adjNext >= 0)
737  {
738  tri = adjNext;
739  vIndex = GetIndexOfVertex(tri, v);
740  GTE_CDT_REQUIRE(vIndex >= 0);
741  link.push_front(std::make_pair(tri, vIndex));
742  }
743  else
744  {
745  // We have reached the other boundary edge that shares v.
746  return true;
747  }
748  }
749  break;
750  }
751  }
752 
753  // Unexpected failure.
755 }
756 
757 template <typename InputType, typename ComputeType>
759 {
760  LogError("CDT failure.");
761 }
762 
763 
764 }
#define GTE_CDT_REQUIRE(c)
bool ProcessInterior(int tri, int v0, int v1, int vNext, int vPrev, std::vector< int > &outEdge)
std::vector< int > const & GetAdjacencies() const
Definition: GteDelaunay2.h:419
GLuint GLfloat GLfloat GLfloat GLfloat GLfloat GLfloat GLfloat t0
Definition: glext.h:9013
#define GTE_CDT_FAILURE_RET(r)
int RetriangulateRRecurse(std::vector< std::array< int, 2 >> const &rBoundary, int i0, int i1, int a0, std::vector< int > &polygon)
bool Connect(int tri, int adj, int v0, int v1)
GLfloat GLfloat v1
Definition: glcorearb.h:812
GLuint GLfloat GLfloat GLfloat GLfloat GLfloat GLfloat GLfloat GLfloat GLfloat t1
Definition: glext.h:9013
PrimalQuery2< ComputeType > mQuery
Definition: GteDelaunay2.h:171
std::array< int, 2 > GetAdjBoundary(int tri, int needBndVertex, int needAdjVIndex) const
ComputeType ComputePSD(int v0, int v1, int v2) const
bool Insert(std::array< int, 2 > const &edge, std::vector< int > &outEdge)
int GetIndexOfVertex(int tri, int v) const
bool operator()(int numVertices, Vector2< InputType > const *vertices, InputType epsilon)
Definition: GteDelaunay2.h:232
std::vector< int > mIndices
Definition: GteDelaunay2.h:179
std::vector< int > mDuplicates
Definition: GteDelaunay2.h:197
bool Retriangulate(std::vector< int > &polygon, std::vector< std::array< int, 2 >> const &lBoundary, std::vector< std::array< int, 2 >> const &rBoundary)
bool ProcessCoincident(int tri, int v0, int v1, int vOther, std::vector< int > &outEdge)
ETManifoldMesh mGraph
Definition: GteDelaunay2.h:178
int ToLine(int i, int v0, int v1) const
GLsizei GLenum const void * indices
Definition: glcorearb.h:401
int RetriangulateLRecurse(std::vector< std::array< int, 2 >> const &lBoundary, int i0, int i1, int a0, std::vector< int > &polygon)
#define LogError(message)
Definition: GteLogger.h:92
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)
GLfloat v0
Definition: glcorearb.h:811
const GLdouble * v
Definition: glcorearb.h:832
GLfloat GLfloat GLfloat v2
Definition: glcorearb.h:813
std::vector< Vector2< ComputeType > > mComputeVertices
Definition: GteDelaunay2.h:170
#define GTE_CDT_REQUIRE_RET(c, r)
std::vector< int > mAdjacencies
Definition: GteDelaunay2.h:180
bool BuildLink(int v, int vTriangle, std::list< std::pair< int, int >> &link, bool &isOpen) const
bool operator()(int numVertices, Vector2< InputType > const *vertices, InputType epsilon)
std::array< int, 2 > GetAdjInterior(int tri, int v0, int v1) const
int SelectSplit(std::vector< std::array< int, 2 >> const &boundary, int i0, int i1) const
std::vector< int > const & GetIndices() const
Definition: GteDelaunay2.h:413
#define GTE_CDT_FAILURE


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