GteDelaunay2.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>
13 #include <Mathematics/GteLine.h>
14 #include <vector>
15 
16 // Delaunay triangulation of points (intrinsic dimensionality 2).
17 // VQ = number of vertices
18 // V = array of vertices
19 // TQ = number of triangles
20 // I = Array of 3-tuples of indices into V that represent the triangles
21 // (3*TQ total elements). Access via GetIndices(*).
22 // A = Array of 3-tuples of indices into I that represent the adjacent
23 // triangles (3*TQ total elements). Access via GetAdjacencies(*).
24 // The i-th triangle has vertices
25 // vertex[0] = V[I[3*i+0]]
26 // vertex[1] = V[I[3*i+1]]
27 // vertex[2] = V[I[3*i+2]]
28 // and edge index pairs
29 // edge[0] = <I[3*i+0],I[3*i+1]>
30 // edge[1] = <I[3*i+1],I[3*i+2]>
31 // edge[2] = <I[3*i+2],I[3*i+0]>
32 // The triangles adjacent to these edges have indices
33 // adjacent[0] = A[3*i+0] is the triangle sharing edge[0]
34 // adjacent[1] = A[3*i+1] is the triangle sharing edge[1]
35 // adjacent[2] = A[3*i+2] is the triangle sharing edge[2]
36 // If there is no adjacent triangle, the A[*] value is set to -1. The
37 // triangle adjacent to edge[j] has vertices
38 // adjvertex[0] = V[I[3*adjacent[j]+0]]
39 // adjvertex[1] = V[I[3*adjacent[j]+1]]
40 // adjvertex[2] = V[I[3*adjacent[j]+2]]
41 // The only way to ensure a correct result for the input vertices (assumed to
42 // be exact) is to choose ComputeType for exact rational arithmetic. You may
43 // use BSNumber. No divisions are performed in this computation, so you do
44 // not have to use BSRational.
45 //
46 // The worst-case choices of N for Real of type BSNumber or BSRational with
47 // integer storage UIntegerFP32<N> are listed in the next table. The numerical
48 // computations are encapsulated in PrimalQuery2<Real>::ToLine and
49 // PrimalQuery2<Real>::ToCircumcircle, the latter query the dominant one in
50 // determining N. We recommend using only BSNumber, because no divisions are
51 // performed in the convex-hull computations.
52 //
53 // input type | compute type | N
54 // -----------+--------------+------
55 // float | BSNumber | 35
56 // double | BSNumber | 263
57 // float | BSRational | 12302
58 // double | BSRational | 92827
59 
60 namespace gte
61 {
62 
63 template <typename InputType, typename ComputeType>
64 class Delaunay2
65 {
66 public:
67  // The class is a functor to support computing the Delaunay triangulation
68  // of multiple data sets using the same class object.
69  virtual ~Delaunay2();
70  Delaunay2();
71 
72  // The input is the array of vertices whose Delaunay triangulation is
73  // required. The epsilon value is used to determine the intrinsic
74  // dimensionality of the vertices (d = 0, 1, or 2). When epsilon is
75  // positive, the determination is fuzzy--vertices approximately the same
76  // point, approximately on a line, or planar. The return value is 'true'
77  // if and only if the hull construction is successful.
78  bool operator()(int numVertices, Vector2<InputType> const* vertices, InputType epsilon);
79 
80  // Dimensional information. If GetDimension() returns 1, the points lie
81  // on a line P+t*D (fuzzy comparison when epsilon > 0). You can sort
82  // these if you need a polyline output by projecting onto the line each
83  // vertex X = P+t*D, where t = Dot(D,X-P).
84  inline InputType GetEpsilon() const;
85  inline int GetDimension() const;
86  inline Line2<InputType> const& GetLine() const;
87 
88  // Member access.
89  inline int GetNumVertices() const;
90  inline int GetNumUniqueVertices() const;
91  inline int GetNumTriangles() const;
92  inline Vector2<InputType> const* GetVertices() const;
93  inline PrimalQuery2<ComputeType> const& GetQuery() const;
94  inline ETManifoldMesh const& GetGraph() const;
95  inline std::vector<int> const& GetIndices() const;
96  inline std::vector<int> const& GetAdjacencies() const;
97 
98  // If 'vertices' has no duplicates, GetDuplicates()[i] = i for all i.
99  // If vertices[i] is the first occurrence of a vertex and if vertices[j]
100  // is found later, then GetDuplicates()[j] = i.
101  inline std::vector<int> const& GetDuplicates() const;
102 
103  // Locate those triangle edges that do not share other triangles. The
104  // returned array has hull.size() = 2*numEdges, each pair representing an
105  // edge. The edges are not ordered, but the pair of vertices for an edge
106  // is ordered so that they conform to a counterclockwise traversal of the
107  // hull. The return value is 'true' iff the dimension is 2.
108  bool GetHull(std::vector<int>& hull) const;
109 
110  // Get the vertex indices for triangle i. The function returns 'true'
111  // when the dimension is 2 and i is a valid triangle index, in which case
112  // the vertices are valid; otherwise, the function returns 'false' and the
113  // vertices are invalid.
114  bool GetIndices(int i, std::array<int, 3>& indices) const;
115 
116  // Get the indices for triangles adjacent to triangle i. The function
117  // returns 'true' when the dimension is 2 and if i is a valid triangle
118  // index, in which case the adjacencies are valid; otherwise, the function
119  // returns 'false' and the adjacencies are invalid.
120  bool GetAdjacencies(int i, std::array<int, 3>& adjacencies) const;
121 
122  // Support for searching the triangulation for a triangle that contains
123  // a point. If there is a containing triangle, the returned value is a
124  // triangle index i with 0 <= i < GetNumTriangles(). If there is not a
125  // containing triangle, -1 is returned. The computations are performed
126  // using exact rational arithmetic.
127  //
128  // The SearchInfo input stores information about the triangle search when
129  // looking for the triangle (if any) that contains p. The first triangle
130  // searched is 'initialTriangle'. On return 'path' stores those (ordered)
131  // triangle indices visited during the search. The last visited triangle
132  // has index 'finalTriangle and vertex indices 'finalV[0,1,2]', stored in
133  // counterclockwise order. The last edge of the search is
134  // <finalV[0],finalV[1]>. For spatially coherent inputs p for numerous
135  // calls to this function, you will want to specify 'finalTriangle' from
136  // the previous call as 'initialTriangle' for the next call, which should
137  // reduce search times.
138  struct SearchInfo
139  {
141  int numPath;
142  std::vector<int> path;
144  std::array<int, 3> finalV;
145  };
146  int GetContainingTriangle(Vector2<InputType> const& p, SearchInfo& info) const;
147 
148 protected:
149  // Support for incremental Delaunay triangulation.
151  bool GetContainingTriangle(int i, std::shared_ptr<Triangle>& tri) const;
152  bool GetAndRemoveInsertionPolygon(int i, std::set<std::shared_ptr<Triangle>>& candidates,
153  std::set<EdgeKey<true>>& boundary);
154  bool Update(int i);
155 
156  // The epsilon value is used for fuzzy determination of intrinsic
157  // dimensionality. If the dimension is 0 or 1, the constructor returns
158  // early. The caller is responsible for retrieving the dimension and
159  // taking an alternate path should the dimension be smaller than 2.
160  // If the dimension is 0, the caller may as well treat all vertices[]
161  // as a single point, say, vertices[0]. If the dimension is 1, the
162  // caller can query for the approximating line and project vertices[]
163  // onto it for further processing.
164  InputType mEpsilon;
167 
168  // The array of vertices used for geometric queries. If you want to be
169  // certain of a correct result, choose ComputeType to be BSNumber.
170  std::vector<Vector2<ComputeType>> mComputeVertices;
172 
173  // The graph information.
179  std::vector<int> mIndices;
180  std::vector<int> mAdjacencies;
181 
182  // If a vertex occurs multiple times in the 'vertices' input to the
183  // constructor, the first processed occurrence of that vertex has an
184  // index stored in this array. If there are no duplicates, then
185  // mDuplicates[i] = i for all i.
186 
188  {
189  ProcessedVertex();
190  ProcessedVertex(Vector2<InputType> const& inVertex, int inLocation);
191  bool operator<(ProcessedVertex const& v) const;
192 
194  int location;
195  };
196 
197  std::vector<int> mDuplicates;
198 
199  // Indexing for the vertices of the triangle adjacent to a vertex. The
200  // edge adjacent to vertex j is <mIndex[j][0], mIndex[j][1]> and is listed
201  // so that the triangle interior is to your left as you walk around the
202  // edges. TODO: Use the "opposite edge" to be consistent with that of
203  // TetrahedronKey. The "opposite" idea extends easily to higher
204  // dimensions.
205  std::array<std::array<int, 2>, 3> mIndex;
206 };
207 
208 
209 template <typename InputType, typename ComputeType>
211 {
212 }
213 
214 template <typename InputType, typename ComputeType>
216  :
217  mEpsilon((InputType)0),
218  mDimension(0),
219  mLine(Vector2<InputType>::Zero(), Vector2<InputType>::Zero()),
220  mNumVertices(0),
222  mNumTriangles(0),
223  mVertices(nullptr)
224 {
225  // INVESTIGATE. If the initialization of mIndex is placed in the
226  // constructor initializer list, MSVS 2012 generates an internal
227  // compiler error.
228  mIndex = { { { 0, 1 }, { 1, 2 }, { 2, 0 } } };
229 }
230 
231 template <typename InputType, typename ComputeType>
233  Vector2<InputType> const* vertices, InputType epsilon)
234 {
235  mEpsilon = std::max(epsilon, (InputType)0);
236  mDimension = 0;
237  mLine.origin = Vector2<InputType>::Zero();
238  mLine.direction = Vector2<InputType>::Zero();
239  mNumVertices = numVertices;
240  mNumUniqueVertices = 0;
241  mNumTriangles = 0;
242  mVertices = vertices;
243  mGraph.Clear();
244  mIndices.clear();
245  mAdjacencies.clear();
246  mDuplicates.resize(std::max(numVertices, 3));
247 
248  int i, j;
249  if (mNumVertices < 3)
250  {
251  // Delaunay2 should be called with at least three points.
252  return false;
253  }
254 
256  if (info.dimension == 0)
257  {
258  // mDimension is 0; mGraph, mIndices, and mAdjacencies are empty
259  return false;
260  }
261 
262  if (info.dimension == 1)
263  {
264  // The set is (nearly) collinear.
265  mDimension = 1;
266  mLine = Line2<InputType>(info.origin, info.direction[0]);
267  return false;
268  }
269 
270  mDimension = 2;
271 
272  // Compute the vertices for the queries.
275  for (i = 0; i < mNumVertices; ++i)
276  {
277  for (j = 0; j < 2; ++j)
278  {
279  mComputeVertices[i][j] = vertices[i][j];
280  }
281  }
282 
283  // Insert the (nondegenerate) triangle constructed by the call to
284  // GetInformation. This is necessary for the circumcircle-visibility
285  // algorithm to work correctly.
286  if (!info.extremeCCW)
287  {
288  std::swap(info.extreme[1], info.extreme[2]);
289  }
290  if (!mGraph.Insert(info.extreme[0], info.extreme[1], info.extreme[2]))
291  {
292  return false;
293  }
294 
295  // Incrementally update the triangulation. The set of processed points
296  // is maintained to eliminate duplicates, either in the original input
297  // points or in the points obtained by snap rounding.
298  std::set<ProcessedVertex> processed;
299  for (i = 0; i < 3; ++i)
300  {
301  j = info.extreme[i];
302  processed.insert(ProcessedVertex(vertices[j], j));
303  mDuplicates[j] = j;
304  }
305  for (i = 0; i < mNumVertices; ++i)
306  {
307  ProcessedVertex v(vertices[i], i);
308  auto iter = processed.find(v);
309  if (iter == processed.end())
310  {
311  if (!Update(i))
312  {
313  // A failure can occur if ComputeType is not an exact
314  // arithmetic type.
315  return false;
316  }
317  processed.insert(v);
318  mDuplicates[i] = i;
319  }
320  else
321  {
322  mDuplicates[i] = iter->location;
323  }
324  }
325  mNumUniqueVertices = static_cast<int>(processed.size());
326 
327  // Assign integer values to the triangles for use by the caller.
328  std::map<std::shared_ptr<Triangle>, int> permute;
329  i = -1;
330  permute[nullptr] = i++;
331  for (auto const& element : mGraph.GetTriangles())
332  {
333  permute[element.second] = i++;
334  }
335 
336  // Put Delaunay triangles into an array (vertices and adjacency info).
337  mNumTriangles = static_cast<int>(mGraph.GetTriangles().size());
338  int numindices = 3 * mNumTriangles;
339  if (numindices > 0)
340  {
341  mIndices.resize(numindices);
342  mAdjacencies.resize(numindices);
343  i = 0;
344  for (auto const& element : mGraph.GetTriangles())
345  {
346  std::shared_ptr<Triangle> tri = element.second;
347  for (j = 0; j < 3; ++j, ++i)
348  {
349  mIndices[i] = tri->V[j];
350  mAdjacencies[i] = permute[tri->T[j].lock()];
351  }
352  }
353  }
354 
355  return true;
356 }
357 
358 template <typename InputType, typename ComputeType> inline
360 {
361  return mEpsilon;
362 }
363 
364 template <typename InputType, typename ComputeType> inline
366 {
367  return mDimension;
368 }
369 
370 template <typename InputType, typename ComputeType> inline
372 {
373  return mLine;
374 }
375 
376 template <typename InputType, typename ComputeType> inline
378 {
379  return mNumVertices;
380 }
381 
382 template <typename InputType, typename ComputeType> inline
384 {
385  return mNumUniqueVertices;
386 }
387 
388 template <typename InputType, typename ComputeType> inline
390 {
391  return mNumTriangles;
392 }
393 
394 template <typename InputType, typename ComputeType> inline
396 {
397  return mVertices;
398 }
399 
400 template <typename InputType, typename ComputeType> inline
402 {
403  return mQuery;
404 }
405 
406 template <typename InputType, typename ComputeType> inline
408 {
409  return mGraph;
410 }
411 
412 template <typename InputType, typename ComputeType> inline
413 std::vector<int> const& Delaunay2<InputType, ComputeType>::GetIndices() const
414 {
415  return mIndices;
416 }
417 
418 template <typename InputType, typename ComputeType> inline
420 {
421  return mAdjacencies;
422 }
423 
424 template <typename InputType, typename ComputeType> inline
426 {
427  return mDuplicates;
428 }
429 
430 template <typename InputType, typename ComputeType>
431 bool Delaunay2<InputType, ComputeType>::GetHull(std::vector<int>& hull) const
432 {
433  if (mDimension == 2)
434  {
435  // Count the number of edges that are not shared by two triangles.
436  int numEdges = 0;
437  for (auto adj : mAdjacencies)
438  {
439  if (adj == -1)
440  {
441  ++numEdges;
442  }
443  }
444 
445  if (numEdges > 0)
446  {
447  // Enumerate the edges.
448  hull.resize(2 * numEdges);
449  int current = 0, i = 0;
450  for (auto adj : mAdjacencies)
451  {
452  if (adj == -1)
453  {
454  int tri = i / 3, j = i % 3;
455  hull[current++] = mIndices[3 * tri + j];
456  hull[current++] = mIndices[3 * tri + ((j + 1) % 3)];
457  }
458  ++i;
459  }
460  return true;
461  }
462  else
463  {
464  LogError("Unexpected. There must be at least one triangle.");
465  }
466  }
467  else
468  {
469  LogError("The dimension must be 2.");
470  }
471  return false;
472 }
473 
474 template <typename InputType, typename ComputeType>
475 bool Delaunay2<InputType, ComputeType>::GetIndices(int i, std::array<int, 3>& indices) const
476 {
477  if (mDimension == 2)
478  {
479  int numTriangles = static_cast<int>(mIndices.size() / 3);
480  if (0 <= i && i < numTriangles)
481  {
482  indices[0] = mIndices[3 * i];
483  indices[1] = mIndices[3 * i + 1];
484  indices[2] = mIndices[3 * i + 2];
485  return true;
486  }
487  }
488  else
489  {
490  LogError("The dimension must be 2.");
491  }
492  return false;
493 }
494 
495 template <typename InputType, typename ComputeType>
496 bool Delaunay2<InputType, ComputeType>::GetAdjacencies(int i, std::array<int, 3>& adjacencies) const
497 {
498  if (mDimension == 2)
499  {
500  int numTriangles = static_cast<int>(mIndices.size() / 3);
501  if (0 <= i && i < numTriangles)
502  {
503  adjacencies[0] = mAdjacencies[3 * i];
504  adjacencies[1] = mAdjacencies[3 * i + 1];
505  adjacencies[2] = mAdjacencies[3 * i + 2];
506  return true;
507  }
508  }
509  else
510  {
511  LogError("The dimension must be 2.");
512  }
513  return false;
514 }
515 
516 template <typename InputType, typename ComputeType>
518  Vector2<InputType> const& p, SearchInfo& info) const
519 {
520  if (mDimension == 2)
521  {
522  Vector2<ComputeType> test{ p[0], p[1] };
523 
524  int numTriangles = static_cast<int>(mIndices.size() / 3);
525  info.path.resize(numTriangles);
526  info.numPath = 0;
527  int triangle;
528  if (0 <= info.initialTriangle && info.initialTriangle < numTriangles)
529  {
530  triangle = info.initialTriangle;
531  }
532  else
533  {
534  info.initialTriangle = 0;
535  triangle = 0;
536  }
537 
538  // Use triangle edges as binary separating lines.
539  for (int i = 0; i < numTriangles; ++i)
540  {
541  int ibase = 3 * triangle;
542  int const* v = &mIndices[ibase];
543 
544  info.path[info.numPath++] = triangle;
545  info.finalTriangle = triangle;
546  info.finalV[0] = v[0];
547  info.finalV[1] = v[1];
548  info.finalV[2] = v[2];
549 
550  if (mQuery.ToLine(test, v[0], v[1]) > 0)
551  {
552  triangle = mAdjacencies[ibase];
553  if (triangle == -1)
554  {
555  info.finalV[0] = v[0];
556  info.finalV[1] = v[1];
557  info.finalV[2] = v[2];
558  return -1;
559  }
560  continue;
561  }
562 
563  if (mQuery.ToLine(test, v[1], v[2]) > 0)
564  {
565  triangle = mAdjacencies[ibase + 1];
566  if (triangle == -1)
567  {
568  info.finalV[0] = v[1];
569  info.finalV[1] = v[2];
570  info.finalV[2] = v[0];
571  return -1;
572  }
573  continue;
574  }
575 
576  if (mQuery.ToLine(test, v[2], v[0]) > 0)
577  {
578  triangle = mAdjacencies[ibase + 2];
579  if (triangle == -1)
580  {
581  info.finalV[0] = v[2];
582  info.finalV[1] = v[0];
583  info.finalV[2] = v[1];
584  return -1;
585  }
586  continue;
587  }
588 
589  return triangle;
590  }
591  }
592  else
593  {
594  LogError("The dimension must be 2.");
595  }
596  return -1;
597 }
598 
599 template <typename InputType, typename ComputeType>
600 bool Delaunay2<InputType, ComputeType>::GetContainingTriangle(int i, std::shared_ptr<Triangle>& tri) const
601 {
602  int numTriangles = static_cast<int>(mGraph.GetTriangles().size());
603  for (int t = 0; t < numTriangles; ++t)
604  {
605  int j;
606  for (j = 0; j < 3; ++j)
607  {
608  int v0 = tri->V[mIndex[j][0]];
609  int v1 = tri->V[mIndex[j][1]];
610  if (mQuery.ToLine(i, v0, v1) > 0)
611  {
612  // Point i sees edge <v0,v1> from outside the triangle.
613  auto adjTri = tri->T[j].lock();
614  if (adjTri)
615  {
616  // Traverse to the triangle sharing the face.
617  tri = adjTri;
618  break;
619  }
620  else
621  {
622  // We reached a hull edge, so the point is outside the
623  // hull. TODO: Once a hull data structure is in place,
624  // return tri->T[j] as the candidate for starting a search
625  // for visible hull edges.
626  return false;
627  }
628  }
629 
630  }
631 
632  if (j == 3)
633  {
634  // The point is inside all four edges, so the point is inside
635  // a triangle.
636  return true;
637  }
638  }
639 
640  LogError("Unexpected termination of GetContainingTriangle.");
641  return false;
642 }
643 
644 template <typename InputType, typename ComputeType>
646  std::set<std::shared_ptr<Triangle>>& candidates, std::set<EdgeKey<true>>& boundary)
647 {
648  // Locate the triangles that make up the insertion polygon.
649  ETManifoldMesh polygon;
650  while (candidates.size() > 0)
651  {
652  std::shared_ptr<Triangle> tri = *candidates.begin();
653  candidates.erase(candidates.begin());
654 
655  for (int j = 0; j < 3; ++j)
656  {
657  auto adj = tri->T[j].lock();
658  if (adj && candidates.find(adj) == candidates.end())
659  {
660  int a0 = adj->V[0];
661  int a1 = adj->V[1];
662  int a2 = adj->V[2];
663  if (mQuery.ToCircumcircle(i, a0, a1, a2) <= 0)
664  {
665  // Point i is in the circumcircle.
666  candidates.insert(adj);
667  }
668  }
669  }
670 
671  if (!polygon.Insert(tri->V[0], tri->V[1], tri->V[2]))
672  {
673  return false;
674  }
675  if (!mGraph.Remove(tri->V[0], tri->V[1], tri->V[2]))
676  {
677  return false;
678  }
679  }
680 
681  // Get the boundary edges of the insertion polygon.
682  for (auto const& element : polygon.GetTriangles())
683  {
684  std::shared_ptr<Triangle> tri = element.second;
685  for (int j = 0; j < 3; ++j)
686  {
687  if (!tri->T[j].lock())
688  {
689  boundary.insert(EdgeKey<true>(tri->V[mIndex[j][0]], tri->V[mIndex[j][1]]));
690  }
691  }
692  }
693  return true;
694 }
695 
696 template <typename InputType, typename ComputeType>
698 {
699  // The return value of mGraph.Insert(...) is nullptr if there was a
700  // failure to insert. The Update function will return 'false' when
701  // the insertion fails.
702 
703  auto const& tmap = mGraph.GetTriangles();
704  std::shared_ptr<Triangle> tri = tmap.begin()->second;
705  if (GetContainingTriangle(i, tri))
706  {
707  // The point is inside the convex hull. The insertion polygon
708  // contains only triangles in the current triangulation; the
709  // hull does not change.
710 
711  // Use a depth-first search for those triangles whose circumcircles
712  // contain point i.
713  std::set<std::shared_ptr<Triangle>> candidates;
714  candidates.insert(tri);
715 
716  // Get the boundary of the insertion polygon C that contains the
717  // triangles whose circumcircles contain point i. C contains the
718  // point i.
719  std::set<EdgeKey<true>> boundary;
720  if (!GetAndRemoveInsertionPolygon(i, candidates, boundary))
721  {
722  return false;
723  }
724 
725  // The insertion polygon consists of the triangles formed by
726  // point i and the faces of C.
727  for (auto const& key : boundary)
728  {
729  int v0 = key.V[0];
730  int v1 = key.V[1];
731  if (mQuery.ToLine(i, v0, v1) < 0)
732  {
733  if (!mGraph.Insert(i, v0, v1))
734  {
735  return false;
736  }
737  }
738  // else: Point i is on an edge of 'tri', so the
739  // subdivision has degenerate triangles. Ignore these.
740  }
741  }
742  else
743  {
744  // The point is outside the convex hull. The insertion polygon
745  // is formed by point i and any triangles in the current
746  // triangulation whose circumcircles contain point i.
747 
748  // Locate the convex hull of the triangles. TODO: Maintain a hull
749  // data structure that is updated incrementally.
750  std::set<EdgeKey<true>> hull;
751  for (auto const& element : tmap)
752  {
753  std::shared_ptr<Triangle> t = element.second;
754  for (int j = 0; j < 3; ++j)
755  {
756  if (!t->T[j].lock())
757  {
758  hull.insert(EdgeKey<true>(t->V[mIndex[j][0]], t->V[mIndex[j][1]]));
759  }
760  }
761  }
762 
763  // TODO: Until the hull change, for now just iterate over all the
764  // hull edges and use the ones visible to point i to locate the
765  // insertion polygon.
766  auto const& emap = mGraph.GetEdges();
767  std::set<std::shared_ptr<Triangle>> candidates;
768  std::set<EdgeKey<true>> visible;
769  for (auto const& key : hull)
770  {
771  int v0 = key.V[0];
772  int v1 = key.V[1];
773  if (mQuery.ToLine(i, v0, v1) > 0)
774  {
775  auto iter = emap.find(EdgeKey<false>(v0, v1));
776  if (iter != emap.end() && iter->second->T[1].lock() == nullptr)
777  {
778  auto adj = iter->second->T[0].lock();
779  if (adj && candidates.find(adj) == candidates.end())
780  {
781  int a0 = adj->V[0];
782  int a1 = adj->V[1];
783  int a2 = adj->V[2];
784  if (mQuery.ToCircumcircle(i, a0, a1, a2) <= 0)
785  {
786  // Point i is in the circumcircle.
787  candidates.insert(adj);
788  }
789  else
790  {
791  // Point i is not in the circumcircle but the hull
792  // edge is visible.
793  visible.insert(key);
794  }
795  }
796  }
797  else
798  {
799  LogError("Unexpected condition (ComputeType not exact?)");
800  return false;
801  }
802  }
803  }
804 
805  // Get the boundary of the insertion subpolygon C that contains the
806  // triangles whose circumcircles contain point i.
807  std::set<EdgeKey<true>> boundary;
808  if (!GetAndRemoveInsertionPolygon(i, candidates, boundary))
809  {
810  return false;
811  }
812 
813  // The insertion polygon P consists of the triangles formed by point i
814  // and the back edges of C *and* the visible edges of mGraph-C.
815  for (auto const& key : boundary)
816  {
817  int v0 = key.V[0];
818  int v1 = key.V[1];
819  if (mQuery.ToLine(i, v0, v1) < 0)
820  {
821  // This is a back edge of the boundary.
822  if (!mGraph.Insert(i, v0, v1))
823  {
824  return false;
825  }
826  }
827  }
828  for (auto const& key : visible)
829  {
830  if (!mGraph.Insert(i, key.V[1], key.V[0]))
831  {
832  return false;
833  }
834  }
835  }
836 
837  return true;
838 }
839 
840 template <typename InputType, typename ComputeType>
842 {
843 }
844 
845 template <typename InputType, typename ComputeType>
847  Vector2<InputType> const& inVertex, int inLocation)
848  :
849  vertex(inVertex),
850  location(inLocation)
851 {
852 }
853 
854 template <typename InputType, typename ComputeType>
856  ProcessedVertex const& v) const
857 {
858  return vertex < v.vertex;
859 }
860 
861 
862 }
Vector2< Real > origin
Definition: GteVector2.h:85
Vector2< InputType > vertex
Definition: GteDelaunay2.h:193
GLint location
Definition: glcorearb.h:800
bool GetAndRemoveInsertionPolygon(int i, std::set< std::shared_ptr< Triangle >> &candidates, std::set< EdgeKey< true >> &boundary)
Definition: GteDelaunay2.h:645
EMap const & GetEdges() const
std::vector< int > const & GetAdjacencies() const
Definition: GteDelaunay2.h:419
void Set(int numVertices, Vector2< Real > const *vertices)
int GetNumVertices() const
Definition: GteDelaunay2.h:377
bool GetHull(std::vector< int > &hull) const
Definition: GteDelaunay2.h:431
std::vector< int > const & GetDuplicates() const
Definition: GteDelaunay2.h:425
ETManifoldMesh const & GetGraph() const
Definition: GteDelaunay2.h:407
GLfloat GLfloat v1
Definition: glcorearb.h:812
PrimalQuery2< ComputeType > mQuery
Definition: GteDelaunay2.h:171
int GetDimension() const
Definition: GteDelaunay2.h:365
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
InputType GetEpsilon() const
Definition: GteDelaunay2.h:359
bool operator<(ProcessedVertex const &v) const
Definition: GteDelaunay2.h:855
ETManifoldMesh mGraph
Definition: GteDelaunay2.h:178
int ToLine(int i, int v0, int v1) const
GLsizei GLenum const void * indices
Definition: glcorearb.h:401
#define LogError(message)
Definition: GteLogger.h:92
Line2< InputType > const & GetLine() const
Definition: GteDelaunay2.h:371
static Vector Zero()
virtual std::shared_ptr< Triangle > Insert(int v0, int v1, int v2)
GLfloat v0
Definition: glcorearb.h:811
int ToCircumcircle(int i, int v0, int v1, int v2) const
GLdouble GLdouble t
Definition: glext.h:239
Vector2< InputType > const * GetVertices() const
Definition: GteDelaunay2.h:395
Vector2< InputType > const * mVertices
Definition: GteDelaunay2.h:177
int GetNumTriangles() const
Definition: GteDelaunay2.h:389
TMap const & GetTriangles() const
int GetNumUniqueVertices() const
Definition: GteDelaunay2.h:383
const GLdouble * v
Definition: glcorearb.h:832
virtual bool Remove(int v0, int v1, int v2)
std::array< int, 3 > finalV
Definition: GteDelaunay2.h:144
PrimalQuery2< ComputeType > const & GetQuery() const
Definition: GteDelaunay2.h:401
Line2< InputType > mLine
Definition: GteDelaunay2.h:166
std::vector< Vector2< ComputeType > > mComputeVertices
Definition: GteDelaunay2.h:170
std::vector< int > path
Definition: GteDelaunay2.h:142
std::vector< int > mAdjacencies
Definition: GteDelaunay2.h:180
int GetContainingTriangle(Vector2< InputType > const &p, SearchInfo &info) const
Definition: GteDelaunay2.h:517
virtual ~Delaunay2()
Definition: GteDelaunay2.h:210
GLfloat GLfloat p
Definition: glext.h:11668
ETManifoldMesh::Triangle Triangle
Definition: GteDelaunay2.h:150
bool Update(int i)
Definition: GteDelaunay2.h:697
InputType mEpsilon
Definition: GteDelaunay2.h:164
std::array< std::array< int, 2 >, 3 > mIndex
Definition: GteDelaunay2.h:205
std::vector< int > const & GetIndices() const
Definition: GteDelaunay2.h:413
Vector2< Real > direction[2]
Definition: GteVector2.h:86


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