GteVertexCollapseMesh.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 <Mathematics/GteVector3.h>
14 #include <LowLevel/GteLogger.h>
15 #include <LowLevel/GteMinHeap.h>
16 #include <set>
17 
18 namespace gte
19 {
20 
21 template <typename Real>
23 {
24 public:
25  // Construction.
26  VertexCollapseMesh(int numPositions, Vector3<Real> const* positions,
27  int numIndices, int const* indices);
28 
29  // Decimate the mesh using vertex collapses
30  struct Record
31  {
32  // The index of the interior vertex that is removed from the mesh.
33  // The triangles adjacent to the vertex are 'removed' from the mesh.
34  // The polygon boundary of the adjacent triangles is triangulated and
35  // the new triangles are 'inserted' into the mesh.
36  int vertex;
37  std::vector<TriangleKey<true>> removed;
38  std::vector<TriangleKey<true>> inserted;
39  };
40 
41  // Return 'true' when a vertex collapse occurs. Once the function returns
42  // 'false', no more vertex collapses are allowed so you may then stop
43  // calling the function. The implementation has several consistency tests
44  // that should not fail with a theoretically correct implementation. If a
45  // test fails, the function returns 'false' and the record.vertex is set to
46  // the invalid integer 0x80000000. When the Logger system is enabled, the
47  // failed tests are reported to any Logger listeners.
48  bool DoCollapse(Record& record);
49 
50  // Access the current state of the mesh, whether the original built in the
51  // constructor or a decimated mesh during DoCollapse calls.
52  inline ETManifoldMesh const& GetMesh() const;
53 
54 private:
56  {
57  VCVertex(int v);
58  static std::shared_ptr<Vertex> Create(int v);
59 
60  // The weight depends on the area of the triangles sharing the vertex
61  // and the lengths of the projections of the adjacent vertices onto
62  // the vertex normal line. A side effect of the call is that the
63  // vertex normal is computed and stored.
64  Real ComputeWeight(Vector3<Real> const* positions);
65 
67  bool isBoundary;
68  };
69 
70  // The functions TriangulateLink and Collapsed return one of the
71  // enumerates described next.
72  //
73  // VCM_NO_MORE_ALLOWED:
74  // Either the mesh has no more interior vertices or a collapse
75  // will lead to a mesh fold-over or to a nonmanifold mesh. The
76  // returned value 'v' is invalid (0x80000000) and 'removed' and
77  // 'inserted' are empty.
78  //
79  // VCM_ALLOWED:
80  // An interior vertex v has been removed. This is allowed using the
81  // following algorithm. The vertex normal is the weighted average
82  // of non-unit-length normals of triangles sharing v. The weights
83  // are the triangle areas. The adjacent vertices are projected onto
84  // a plane containing v and having normal equal to the vertex normal.
85  // If the projection is a simple polygon in the plane, the collapse
86  // is allowed. The triangles sharing v are 'removed', the polygon is
87  // triangulated, and the new triangles are 'inserted' into the mesh.
88  //
89  // VCM_DEFERRED:
90  // If the projection polygon described in the previous case is not
91  // simple (at least one pair of edges overlaps at some edge-interior
92  // point), the collapse would produce a fold-over in the mesh. We
93  // do not collapse in this case. It is possible that such a vertex
94  // occurs in a later collapse as its neighbors are adjusted by
95  // collapses. When this case occurs, v is valid (even though the
96  // collapse was not allowed) but 'removed' and 'inserted' are empty.
97  //
98  // VCM_UNEXPECTED_ERROR:
99  // The code has several tests for conditions that are not expected
100  // to occur for a theoretically correct implementation. If you
101  // receive this error, file a bug report and provide a data set
102  // that caused the error.
103  enum
104  {
109  };
110 
111  int TriangulateLink(std::shared_ptr<VCVertex> const& vertex, std::vector<TriangleKey<true>>& removed,
112  std::vector<TriangleKey<true>>& inserted, std::vector<int>& linkVertices) const;
113 
114  int Collapsed(std::vector<TriangleKey<true>> const& removed,
115  std::vector<TriangleKey<true>> const& inserted, std::vector<int> const& linkVertices);
116 
120 
122  std::map<int, typename MinHeap<int, Real>::Record*> mHeapRecords;
123 };
124 
125 
126 template <typename Real>
128  Vector3<Real> const* positions, int numIndices, int const* indices)
129  :
130  mNumPositions(numPositions),
131  mPositions(positions),
132  mMesh(VCVertex::Create)
133 {
134  if (numPositions <= 0 || !positions || numIndices < 3 || !indices)
135  {
136  mNumPositions = 0;
137  mPositions = nullptr;
138  return;
139  }
140 
141  // Build the manifold mesh from the inputs.
142  int numTriangles = numIndices / 3;
143  int const* current = indices;
144  for (int t = 0; t < numTriangles; ++t)
145  {
146  int v0 = *current++;
147  int v1 = *current++;
148  int v2 = *current++;
149  mMesh.Insert(v0, v1, v2);
150  }
151 
152  // Locate the vertices (if any) on the mesh boundary.
153  auto const& vmap = mMesh.GetVertices();
154  for (auto const& eelement : mMesh.GetEdges())
155  {
156  auto edge = eelement.second;
157  if (!edge->T[1].lock())
158  {
159  for (int i = 0; i < 2; ++i)
160  {
161  auto velement = vmap.find(edge->V[i]);
162  auto vertex = std::static_pointer_cast<VCVertex>(velement->second);
163  vertex->isBoundary = true;
164  }
165  }
166  }
167 
168  // Build the priority queue of weights for the interior vertices.
169  mMinHeap.Reset((int)vmap.size());
170  for (auto const& velement : vmap)
171  {
172  auto vertex = std::static_pointer_cast<VCVertex>(velement.second);
173 
174  Real weight;
175  if (vertex->isBoundary)
176  {
177  weight = std::numeric_limits<Real>::max();
178  }
179  else
180  {
181  weight = vertex->ComputeWeight(mPositions);
182  }
183 
184  auto record = mMinHeap.Insert(velement.first, weight);
185  mHeapRecords.insert(std::make_pair(velement.first, record));
186  }
187 }
188 
189 template <typename Real>
191 {
192  record.vertex = 0x80000000;
193  record.removed.clear();
194  record.inserted.clear();
195 
196  if (mNumPositions == 0)
197  {
198  // The constructor failed, so there is nothing to collapse.
199  return false;
200  }
201 
202  while (mMinHeap.GetNumElements() > 0)
203  {
204  int v = -1;
205  Real weight = std::numeric_limits<Real>::max();
206  mMinHeap.GetMinimum(v, weight);
207  if (weight == std::numeric_limits<Real>::max())
208  {
209  // There are no more interior vertices to collapse.
210  return false;
211  }
212 
213  auto const& vmap = mMesh.GetVertices();
214  auto velement = vmap.find(v);
215  if (velement == vmap.end())
216  {
217  LogError("Unexpected condition.");
218  return false;
219  }
220 
221  auto vertex = std::static_pointer_cast<VCVertex>(velement->second);
222  std::vector<TriangleKey<true>> removed, inserted;
223  std::vector<int> linkVertices;
224  int result = TriangulateLink(vertex, removed, inserted, linkVertices);
225  if (result == VCM_UNEXPECTED_ERROR)
226  {
227  return false;
228  }
229 
230  if (result == VCM_ALLOWED)
231  {
232  result = Collapsed(removed, inserted, linkVertices);
233  if (result == VCM_UNEXPECTED_ERROR)
234  {
235  return false;
236  }
237 
238  if (result == VCM_ALLOWED)
239  {
240  // Remove the vertex and associated weight.
241  mMinHeap.Remove(v, weight);
242  mHeapRecords.erase(v);
243 
244  // Update the weights of the link vertices.
245  for (auto vlink : linkVertices)
246  {
247  velement = vmap.find(vlink);
248  if (velement == vmap.end())
249  {
250  LogError("Unexpected condition.");
251  return false;
252  }
253 
254  vertex = std::static_pointer_cast<VCVertex>(velement->second);
255  if (!vertex->isBoundary)
256  {
257  auto iter = mHeapRecords.find(vlink);
258  if (iter == mHeapRecords.end())
259  {
260  LogError("Unexpected condition.");
261  return false;
262  }
263 
264  weight = vertex->ComputeWeight(mPositions);
265  mMinHeap.Update(iter->second, weight);
266  }
267  }
268 
269  record.vertex = v;
270  record.removed = std::move(removed);
271  record.inserted = std::move(inserted);
272  return true;
273  }
274  // else: result == VCM_DEFERRED
275  }
276 
277  // To get here, result must be VCM_DEFERRED. The vertex collapse
278  // would cause mesh fold-over. Temporarily set the edge weight to
279  // infinity. After removal of other triangles, the vertex weight
280  // will be updated to a finite value and the vertex possibly can be
281  // removed at that time.
282  auto iter = mHeapRecords.find(v);
283  if (iter == mHeapRecords.end())
284  {
285  LogError("Unexpected condition.");
286  return false;
287  }
288  mMinHeap.Update(iter->second, std::numeric_limits<Real>::max());
289  }
290 
291  // We do not expect to reach this line of code, even for a closed mesh.
292  // However, the compiler does not know this, yet requires a return value.
293  return false;
294 }
295 
296 template <typename Real> inline
298 {
299  return mMesh;
300 }
301 
302 template <typename Real>
303 int VertexCollapseMesh<Real>::TriangulateLink(std::shared_ptr<VCVertex> const& vertex,
304  std::vector<TriangleKey<true>>& removed, std::vector<TriangleKey<true>>& inserted,
305  std::vector<int>& linkVertices) const
306 {
307  // Create the (CCW) polygon boundary of the link of the vertex. The
308  // incoming vertex is interior, so the number of triangles sharing the
309  // vertex is equal to the number of vertices of the polygon. A
310  // precondition of the function call is that the vertex normal has already
311  // been computed.
312 
313  // Get the edges of the link that are opposite the incoming vertex.
314  int const numVertices = static_cast<int>(vertex->TAdjacent.size());
315  removed.resize(numVertices);
316  int j = 0;
317  std::map<int, int> edgeMap;
318  for (auto tri : vertex->TAdjacent)
319  {
320  for (int i = 0; i < 3; ++i)
321  {
322  if (tri->V[i] == vertex->V)
323  {
324  edgeMap.insert(std::make_pair(tri->V[(i + 1) % 3], tri->V[(i + 2) % 3]));
325  break;
326  }
327  }
328  removed[j++] = TriangleKey<true>(tri->V[0], tri->V[1], tri->V[2]);
329  }
330  if (edgeMap.size() != vertex->TAdjacent.size())
331  {
332  LogError("Unexpected condition.");
333  return VCM_UNEXPECTED_ERROR;
334  }
335 
336  // Connect the edges into a polygon.
337  linkVertices.resize(numVertices);
338  auto iter = edgeMap.begin();
339  for (int i = 0; i < numVertices; ++i)
340  {
341  linkVertices[i] = iter->first;
342  iter = edgeMap.find(iter->second);
343  if (iter == edgeMap.end())
344  {
345  LogError("Unexpected condition.");
346  return VCM_UNEXPECTED_ERROR;
347  }
348  }
349  if (iter->first != linkVertices[0])
350  {
351  LogError("Unexpected condition.");
352  return VCM_UNEXPECTED_ERROR;
353  }
354 
355  // Project the polygon onto the plane containing the incoming vertex and
356  // having the vertex normal. The projected polygon is computed so that
357  // the incoming vertex is projected to (0,0).
358  Vector3<Real> center = mPositions[vertex->V];
359  Vector3<Real> basis[3];
360  basis[0] = vertex->normal;
361  ComputeOrthogonalComplement(1, basis);
362  std::vector<Vector2<Real>> projected(numVertices);
363  std::vector<int> indices(numVertices);
364  for (int i = 0; i < numVertices; ++i)
365  {
366  Vector3<Real> diff = mPositions[linkVertices[i]] - center;
367  projected[i][0] = Dot(basis[1], diff);
368  projected[i][1] = Dot(basis[2], diff);
369  indices[i] = i;
370  }
371 
372  // The polygon must be simple in order to triangulate it.
373  Polygon2<Real> polygon(projected.data(), numVertices, indices.data(), true);
374  if (polygon.IsSimple())
375  {
376  TriangulateEC<Real, Real> triangulator(numVertices, projected.data());
377  triangulator();
378  auto const& triangles = triangulator.GetTriangles();
379  if (triangles.size() == 0)
380  {
381  LogError("Unexpected condition.");
382  return VCM_UNEXPECTED_ERROR;
383  }
384 
385  int const numTriangles = static_cast<int>(triangles.size());
386  inserted.resize(numTriangles);
387  for (int t = 0; t < numTriangles; ++t)
388  {
389  inserted[t] = TriangleKey<true>(
390  linkVertices[triangles[t][0]],
391  linkVertices[triangles[t][1]],
392  linkVertices[triangles[t][2]]);
393  }
394  return VCM_ALLOWED;
395  }
396  else
397  {
398  return VCM_DEFERRED;
399  }
400 }
401 
402 template <typename Real>
404  std::vector<TriangleKey<true>> const& inserted, std::vector<int> const& linkVertices)
405 {
406  // The triangles that were disconnected from the link edges are guaranteed
407  // to allow manifold reconnection to 'inserted' triangles. On the
408  // insertion, each diagonal of the link becomes a mesh edge and shares two
409  // (link) triangles. It is possible that the mesh already contains the
410  // (diagonal) edge, which will lead to a nonmanifold connection, which we
411  // cannot allow. The following code traps this condition and restores the
412  // mesh to its state before the 'Remove(...)' call.
413  bool isCollapsible = true;
414  auto const& emap = mMesh.GetEdges();
415  std::set<EdgeKey<false>> edges;
416  for (auto const& tri : inserted)
417  {
418  for (int k0 = 2, k1 = 0; k1 < 3; k0 = k1++)
419  {
420  EdgeKey<false> edge(tri.V[k0], tri.V[k1]);
421  if (edges.find(edge) == edges.end())
422  {
423  edges.insert(edge);
424  }
425  else
426  {
427  // The edge has been visited twice, so it is a diagonal of
428  // the link.
429 
430  auto eelement = emap.find(edge);
431  if (eelement != emap.end())
432  {
433  if (eelement->second->T[1].lock())
434  {
435  // The edge will not allow a manifold connection.
436  isCollapsible = false;
437  break;
438  }
439  }
440 
441  edges.erase(edge);
442  }
443  };
444 
445  if (!isCollapsible)
446  {
447  return VCM_DEFERRED;
448  }
449  }
450 
451  // Remove the old triangle neighborhood, which will lead to the vertex
452  // itself being removed from the mesh.
453  for (auto tri : removed)
454  {
455  mMesh.Remove(tri.V[0], tri.V[1], tri.V[2]);
456  }
457 
458  // Insert the new triangulation.
459  for (auto const& tri : inserted)
460  {
461  mMesh.Insert(tri.V[0], tri.V[1], tri.V[2]);
462  }
463 
464  // If the Remove(...) calls remove a boundary vertex that is in the link
465  // vertices, the Insert(...) calls will insert the boundary vertex again.
466  // We must re-tag those boundary vertices.
467  auto const& vmap = mMesh.GetVertices();
468  size_t const numVertices = linkVertices.size();
469  for (size_t i0 = numVertices - 1, i1 = 0; i1 < numVertices; i0 = i1++)
470  {
471  EdgeKey<false> ekey(linkVertices[i0], linkVertices[i1]);
472  auto eelement = emap.find(ekey);
473  if (eelement == emap.end())
474  {
475  LogError("Unexpected condition.");
476  return VCM_UNEXPECTED_ERROR;
477  }
478 
479  auto edge = eelement->second;
480  if (!edge)
481  {
482  LogError("Unexpected condition.");
483  return VCM_UNEXPECTED_ERROR;
484  }
485 
486  if (edge->T[0].lock() && !edge->T[1].lock())
487  {
488  for (int k = 0; k < 2; ++k)
489  {
490  auto velement = vmap.find(edge->V[k]);
491  if (velement == vmap.end())
492  {
493  LogError("Unexpected condition.");
494  return VCM_UNEXPECTED_ERROR;
495  }
496 
497  auto vertex = std::static_pointer_cast<VCVertex>(velement->second);
498  vertex->isBoundary = true;
499  }
500  }
501  }
502 
503  return VCM_ALLOWED;
504 }
505 
506 template <typename Real>
508  :
509  VETManifoldMesh::Vertex(v),
510  normal(Vector3<Real>::Zero()),
511  isBoundary(false)
512 {
513 }
514 
515 template <typename Real>
516 std::shared_ptr<VETManifoldMesh::Vertex> VertexCollapseMesh<Real>::VCVertex::Create(int v)
517 {
518  return std::make_shared<VCVertex>(v);
519 }
520 
521 template <typename Real>
523 {
524  Real weight = (Real)0;
525 
526  normal = { (Real)0, (Real)0, (Real)0 };
527  for (auto const& tri : TAdjacent)
528  {
529  Vector3<Real> E0 = positions[tri->V[1]] - positions[tri->V[0]];
530  Vector3<Real> E1 = positions[tri->V[2]] - positions[tri->V[0]];
531  Vector3<Real> N = Cross(E0, E1);
532  normal += N;
533  weight += Length(N);
534  }
535  Normalize(normal);
536 
537  for (int index : VAdjacent)
538  {
539  Vector3<Real> diff = positions[index] - positions[V];
540  weight += fabs(Dot(normal, diff));
541  }
542 
543  return weight;
544 }
545 
546 }
std::vector< TriangleKey< true > > inserted
Record * Insert(KeyType const &key, ValueType const &value)
Definition: GteMinHeap.h:217
EMap const & GetEdges() const
GLfloat GLfloat v1
Definition: glcorearb.h:812
int GetNumElements() const
Definition: GteMinHeap.h:195
GLuint GLuint GLfloat weight
Definition: glext.h:9668
std::set< std::shared_ptr< Triangle > > TAdjacent
bool DoCollapse(Record &record)
void Update(Record *record, ValueType const &value)
Definition: GteMinHeap.h:322
void Reset(int maxElements)
Definition: GteMinHeap.h:174
int Collapsed(std::vector< TriangleKey< true >> const &removed, std::vector< TriangleKey< true >> const &inserted, std::vector< int > const &linkVertices)
GLsizei GLenum const void * indices
Definition: glcorearb.h:401
#define LogError(message)
Definition: GteLogger.h:92
static std::shared_ptr< Vertex > Create(int v)
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
bool Remove(KeyType &key, ValueType &value)
Definition: GteMinHeap.h:262
Real Normalize(GVector< Real > &v, bool robust=false)
Definition: GteGVector.h:454
GLfloat v0
Definition: glcorearb.h:811
GLdouble GLdouble t
Definition: glext.h:239
DualQuaternion< Real > Cross(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
virtual bool Remove(int v0, int v1, int v2) override
std::vector< std::array< int, 3 > > const & GetTriangles() const
Real ComputeWeight(Vector3< Real > const *positions)
DualQuaternion< Real > Length(DualQuaternion< Real > const &d, bool robust=false)
const GLdouble * v
Definition: glcorearb.h:832
int TriangulateLink(std::shared_ptr< VCVertex > const &vertex, std::vector< TriangleKey< true >> &removed, std::vector< TriangleKey< true >> &inserted, std::vector< int > &linkVertices) const
ETManifoldMesh const & GetMesh() const
GLfloat GLfloat GLfloat v2
Definition: glcorearb.h:813
GLuint index
Definition: glcorearb.h:781
Real ComputeOrthogonalComplement(int numInputs, Vector2< Real > *v, bool robust=false)
Definition: GteVector2.h:123
bool GetMinimum(KeyType &key, ValueType &value) const
Definition: GteMinHeap.h:201
std::map< int, typename MinHeap< int, Real >::Record * > mHeapRecords
std::vector< TriangleKey< true > > removed
GLuint64EXT * result
Definition: glext.h:10003
MinHeap< int, Real > mMinHeap
virtual std::shared_ptr< Triangle > Insert(int v0, int v1, int v2) override
VMap const & GetVertices() const
Vector3< Real > const * mPositions
VertexCollapseMesh(int numPositions, Vector3< Real > const *positions, int numIndices, int const *indices)


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