VHACD.h
Go to the documentation of this file.
1 /* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com)
2  All rights reserved.
3 
4 
5  Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
6  following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following
9  disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
12  disclaimer in the documentation and/or other materials provided with the distribution.
13 
14  3. The names of the contributors may not be used to endorse or promote products derived from this software without
15  specific prior written permission.
16 
17  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
18  INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
21  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
22  WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
23  THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
24  */
25 #pragma once
26 #ifndef VHACD_H
27 #define VHACD_H
28 
29 // Please view this slide deck which describes usage and how the algorithm works.
30 // https://docs.google.com/presentation/d/1OZ4mtZYrGEC8qffqb8F7Le2xzufiqvaPpRbLHKKgTIM/edit?usp=sharing
31 
32 // VHACD is now a header only library.
33 // In just *one* of your CPP files *before* you include 'VHACD.h' you must declare
34 // #define ENABLE_VHACD_IMPLEMENTATION 1
35 // This will compile the implementation code into your project. If you don't
36 // have this define, you will get link errors since the implementation code will
37 // not be present. If you define it more than once in your code base, you will get
38 // link errors due to a duplicate implementation. This is the same pattern used by
39 // ImGui and StbLib and other popular open source libraries.
40 
41 #define VHACD_VERSION_MAJOR 4
42 #define VHACD_VERSION_MINOR 1
43 
44 // Changes for version 4.1
45 //
46 // Various minor tweaks mostly to the test application and some default values.
47 
48 // Changes for version 4.0
49 //
50 // * The code has been significantly refactored to be cleaner and easier to maintain
51 // * All OpenCL related code removed
52 // * All Bullet code removed
53 // * All SIMD code removed
54 // * Old plane splitting code removed
55 //
56 // * The code is now delivered as a single header file 'VHACD.h' which has both the API
57 // * declaration as well as the implementation. Simply add '#define ENABLE_VHACD_IMPLEMENTATION 1'
58 // * to any CPP in your application prior to including 'VHACD.h'. Only do this in one CPP though.
59 // * If you do not have this define once, you will get link errors since the implementation code
60 // * will not be compiled in. If you have this define more than once, you are likely to get
61 // * duplicate symbol link errors.
62 //
63 // * Since the library is now delivered as a single header file, we do not provide binaries
64 // * or build scripts as these are not needed.
65 //
66 // * The old DebugView and test code has all been removed and replaced with a much smaller and
67 // * simpler test console application with some test meshes to work with.
68 //
69 // * The convex hull generation code has changed. The previous version came from Bullet.
70 // * However, the new version is courtesy of Julio Jerez, the author of the Newton
71 // * physics engine. His new version is faster and more numerically stable.
72 //
73 // * The code can now detect if the input mesh is, itself, already a convex object and
74 // * can early out.
75 //
76 // * Significant performance improvements have been made to the code and it is now much
77 // * faster, stable, and is easier to tune than previous versions.
78 //
79 // * A bug was fixed with the shrink wrapping code (project hull vertices) that could
80 // * sometime produce artifacts in the results. The new version uses a 'closest point'
81 // * algorithm that is more reliable.
82 //
83 // * You can now select which 'fill mode' to use. For perfectly closed meshes, the default
84 // * behavior using a flood fill generally works fine. However, some meshes have small
85 // * holes in them and therefore the flood fill will fail, treating the mesh as being
86 // * hollow. In these cases, you can use the 'raycast' fill option to determine which
87 // * parts of the voxelized mesh are 'inside' versus being 'outside'. Finally, there
88 // * are some rare instances where a user might actually want the mesh to be treated as
89 // * hollow, in which case you can pass in 'surface' only.
90 // *
91 // * A new optional virtual interface called 'IUserProfiler' was provided.
92 // * This allows the user to provide an optional profiling callback interface to assist in
93 // * diagnosing performance issues. This change was made by Danny Couture at Epic for the UE4 integration.
94 // * Some profiling macros were also declared in support of this feature.
95 // *
96 // * Another new optional virtual interface called 'IUserTaskRunner' was provided.
97 // * This interface is used to run logical 'tasks' in a background thread. If none is provided
98 // * then a default implementation using std::thread will be executed.
99 // * This change was made by Danny Couture at Epic to speed up the voxelization step.
100 // *
101 
102 // The history of V-HACD:
103 //
104 // The initial version was written by John W. Ratcliff and was called 'ACD'
105 // This version did not perform CSG operations on the source mesh, so if you
106 // recursed too deeply it would produce hollow results.
107 //
108 // The next version was written by Khaled Mamou and was called 'HACD'
109 // In this version Khaled tried to perform a CSG operation on the source
110 // mesh to produce more robust results. However, Khaled learned that the
111 // CSG library he was using had licensing issues so he started work on the
112 // next version.
113 //
114 // The next version was called 'V-HACD' because Khaled made the observation
115 // that plane splitting would be far easier to implement working in voxel space.
116 //
117 // V-HACD has been integrated into UE4, Blender, and a number of other projects.
118 // This new release, version4, is a significant refactor of the code to fix
119 // some bugs, improve performance, and to make the codebase easier to maintain
120 // going forward.
121 #include <tesseract_common/macros.h>
123 
124 #include <stdint.h>
125 #include <functional>
126 
127 #include <vector>
128 #include <array>
129 #include <cmath>
130 #include <algorithm>
131 
132 namespace VHACD
133 {
134 struct Vertex
135 {
136  double mX;
137  double mY;
138  double mZ;
139 
140  Vertex() = default;
141  Vertex(double x, double y, double z) : mX(x), mY(y), mZ(z) {}
142 
143  const double& operator[](size_t idx) const
144  {
145  switch (idx)
146  {
147  case 0:
148  return mX;
149  case 1:
150  return mY;
151  case 2:
152  return mZ;
153  };
154  return mX;
155  }
156 };
157 
158 struct Triangle
159 {
160  uint32_t mI0;
161  uint32_t mI1;
162  uint32_t mI2;
163 
164  Triangle() = default;
165  Triangle(uint32_t i0, uint32_t i1, uint32_t i2) : mI0(i0), mI1(i1), mI2(i2) {}
166 };
167 
168 template <typename T>
169 class Vector3
170 {
171 public:
172  /*
173  * Getters
174  */
175  T& operator[](size_t i);
176  const T& operator[](size_t i) const;
177  T& GetX();
178  T& GetY();
179  T& GetZ();
180  const T& GetX() const;
181  const T& GetY() const;
182  const T& GetZ() const;
183 
184  /*
185  * Normalize and norming
186  */
187  T Normalize();
189  T GetNorm() const;
190  T GetNormSquared() const;
191  int LongestAxis() const;
192 
193  /*
194  * Vector-vector operations
195  */
196  Vector3& operator=(const Vector3& rhs);
197  Vector3& operator+=(const Vector3& rhs);
198  Vector3& operator-=(const Vector3& rhs);
199 
200  Vector3 CWiseMul(const Vector3& rhs) const;
201  Vector3 Cross(const Vector3& rhs) const;
202  T Dot(const Vector3& rhs) const;
203  Vector3 operator+(const Vector3& rhs) const;
204  Vector3 operator-(const Vector3& rhs) const;
205 
206  /*
207  * Vector-scalar operations
208  */
209  Vector3& operator-=(T a);
210  Vector3& operator+=(T a);
211  Vector3& operator/=(T a);
212  Vector3& operator*=(T a);
213 
214  Vector3 operator*(T rhs) const;
215  Vector3 operator/(T rhs) const;
216 
217  /*
218  * Unary operations
219  */
220  Vector3 operator-() const;
221 
222  /*
223  * Comparison operators
224  */
225  bool operator<(const Vector3& rhs) const;
226  bool operator>(const Vector3& rhs) const;
227 
228  /*
229  * Returns true if all elements of *this are greater than or equal to all elements of rhs, coefficient wise
230  * LE is less than or equal
231  */
232  bool CWiseAllGE(const Vector3<T>& rhs) const;
233  bool CWiseAllLE(const Vector3<T>& rhs) const;
234 
235  Vector3 CWiseMin(const Vector3& rhs) const;
236  Vector3 CWiseMax(const Vector3& rhs) const;
237  T MinCoeff() const;
238  T MaxCoeff() const;
239 
240  T MinCoeff(uint32_t& idx) const;
241  T MaxCoeff(uint32_t& idx) const;
242 
243  /*
244  * Constructors
245  */
246  Vector3() = default;
247  Vector3(T a);
248  Vector3(T x, T y, T z);
249  Vector3(const Vector3& rhs);
250  ~Vector3() = default;
251 
252  template <typename U>
253  Vector3(const Vector3<U>& rhs);
254 
255  Vector3(const VHACD::Vertex&);
256  Vector3(const VHACD::Triangle&);
257 
258  operator VHACD::Vertex() const;
259 
260 private:
261  std::array<T, 3> m_data{ T(0.0) };
262 };
263 
265 
267 {
268  BoundsAABB() = default;
269  BoundsAABB(const std::vector<VHACD::Vertex>& points);
270  BoundsAABB(const Vect3& min, const Vect3& max);
271 
272  BoundsAABB Union(const BoundsAABB& b);
273 
274  bool Intersects(const BoundsAABB& b) const;
275 
276  double SurfaceArea() const;
277  double Volume() const;
278 
279  BoundsAABB Inflate(double ratio) const;
280 
281  VHACD::Vect3 ClosestPoint(const VHACD::Vect3& p) const;
282 
283  VHACD::Vect3& GetMin();
284  VHACD::Vect3& GetMax();
285  const VHACD::Vect3& GetMin() const;
286  const VHACD::Vect3& GetMax() const;
287 
288  VHACD::Vect3 GetSize() const;
289  VHACD::Vect3 GetCenter() const;
290 
291  VHACD::Vect3 m_min{ double(0.0) };
292  VHACD::Vect3 m_max{ double(0.0) };
293 };
294 
307 enum class FillMode
308 {
309  FLOOD_FILL, // This is the default behavior, after the voxelization step it uses a flood fill to determine 'inside'
310  // from 'outside'. However, meshes with holes can fail and create hollow results.
311  SURFACE_ONLY, // Only consider the 'surface', will create 'skins' with hollow centers.
312  RAYCAST_FILL, // Uses raycasting to determine inside from outside.
313 };
314 
315 class IVHACD
316 {
317 public:
324  {
325  public:
326  virtual ~IUserCallback(){};
327 
336  virtual void Update(const double overallProgress,
337  const double stageProgress,
338  const char* const stage,
339  const char* operation) = 0;
340 
341  // This is an optional user callback which is only called when running V-HACD asynchronously.
342  // This is a callback performed to notify the user that the
343  // convex decomposition background process is completed. This call back will occur from
344  // a different thread so the user should take that into account.
345  virtual void NotifyVHACDComplete() {}
346  };
347 
352  {
353  public:
354  virtual ~IUserLogger(){};
355  virtual void Log(const char* const msg) = 0;
356  };
357 
364  {
365  public:
366  virtual ~IUserTaskRunner(){};
367  virtual void* StartTask(std::function<void()> func) = 0;
368  virtual void JoinTask(void* Task) = 0;
369  };
370 
376  {
377  public:
378  std::vector<VHACD::Vertex> m_points;
379  std::vector<VHACD::Triangle> m_triangles;
380 
381  double m_volume{ 0 }; // The volume of the convex hull
382  VHACD::Vect3 m_center{ 0, 0, 0 }; // The centroid of the convex hull
383  uint32_t m_meshId{ 0 }; // A unique id for this convex hull
384  VHACD::Vect3 mBmin; // Bounding box minimum of the AABB
385  VHACD::Vect3 mBmax; // Bounding box maximum of the AABB
386  };
387 
392  {
393  public:
394  IUserCallback* m_callback{ nullptr }; // Optional user provided callback interface for progress
395  IUserLogger* m_logger{ nullptr }; // Optional user provided callback interface for log messages
396  IUserTaskRunner* m_taskRunner{ nullptr }; // Optional user provided interface for creating tasks
397  uint32_t m_maxConvexHulls{ 64 }; // The maximum number of convex hulls to produce
398  uint32_t m_resolution{ 400000 }; // The voxel resolution to use
399  double m_minimumVolumePercentErrorAllowed{ 1 }; // if the voxels are within 1% of the volume of the hull, we
400  // consider this a close enough approximation
401  uint32_t m_maxRecursionDepth{ 10 }; // The maximum recursion depth
402  bool m_shrinkWrap{ true }; // Whether or not to shrinkwrap the voxel positions to the source mesh on output
403  FillMode m_fillMode{ FillMode::FLOOD_FILL }; // How to fill the interior of the voxelized mesh
404  uint32_t m_maxNumVerticesPerCH{ 64 }; // The maximum number of vertices allowed in any output convex hull
405  bool m_asyncACD{ true }; // Whether or not to run asynchronously, taking advantage of additional cores
406  uint32_t m_minEdgeLength{ 2 }; // Once a voxel patch has an edge length of less than 4 on all 3 sides, we don't
407  // keep recursing
408  bool m_findBestPlane{ false }; // Whether or not to attempt to split planes along the best location. Experimental
409  // feature. False by default.
410  };
411 
416  virtual void Cancel() = 0;
417 
428  virtual bool Compute(const float* const points,
429  const uint32_t countPoints,
430  const uint32_t* const triangles,
431  const uint32_t countTriangles,
432  const Parameters& params) = 0;
433 
444  virtual bool Compute(const double* const points,
445  const uint32_t countPoints,
446  const uint32_t* const triangles,
447  const uint32_t countTriangles,
448  const Parameters& params) = 0;
449 
455  virtual uint32_t GetNConvexHulls() const = 0;
456 
464  virtual bool GetConvexHull(const uint32_t index, ConvexHull& ch) const = 0;
465 
469  virtual void Clean() = 0; // release internally allocated memory
470 
474  virtual void Release() = 0; // release IVHACD
475 
476  // Will compute the center of mass of the convex hull decomposition results and return it
477  // in 'centerOfMass'. Returns false if the center of mass could not be computed.
478  virtual bool ComputeCenterOfMass(double centerOfMass[3]) const = 0;
479 
480  // In synchronous mode (non-multi-threaded) the state is always 'ready'
481  // In asynchronous mode, this returns true if the background thread is not still actively computing
482  // a new solution. In an asynchronous config the 'IsReady' call will report any update or log
483  // messages in the caller's current thread.
484  virtual bool IsReady() const { return true; }
485 
496  virtual uint32_t findNearestConvexHull(const double pos[3], double& distanceToHull) = 0;
497 
498 protected:
499  virtual ~IVHACD() {}
500 };
501 /*
502  * Out of line definitions
503  */
504 
505 template <typename T>
506 T clamp(const T& v, const T& lo, const T& hi)
507 {
508  if (v < lo)
509  {
510  return lo;
511  }
512  if (v > hi)
513  {
514  return hi;
515  }
516  return v;
517 }
518 
519 /*
520  * Getters
521  */
522 template <typename T>
523 inline T& Vector3<T>::operator[](size_t i)
524 {
525  return m_data[i];
526 }
527 
528 template <typename T>
529 inline const T& Vector3<T>::operator[](size_t i) const
530 {
531  return m_data[i];
532 }
533 
534 template <typename T>
535 inline T& Vector3<T>::GetX()
536 {
537  return m_data[0];
538 }
539 
540 template <typename T>
541 inline T& Vector3<T>::GetY()
542 {
543  return m_data[1];
544 }
545 
546 template <typename T>
547 inline T& Vector3<T>::GetZ()
548 {
549  return m_data[2];
550 }
551 
552 template <typename T>
553 inline const T& Vector3<T>::GetX() const
554 {
555  return m_data[0];
556 }
557 
558 template <typename T>
559 inline const T& Vector3<T>::GetY() const
560 {
561  return m_data[1];
562 }
563 
564 template <typename T>
565 inline const T& Vector3<T>::GetZ() const
566 {
567  return m_data[2];
568 }
569 
570 /*
571  * Normalize and norming
572  */
573 template <typename T>
575 {
576  T n = GetNorm();
577  if (n != T(0.0))
578  (*this) /= n;
579  return n;
580 }
581 
582 template <typename T>
584 {
585  Vector3<T> ret = *this;
586  T n = GetNorm();
587  if (n != T(0.0))
588  ret /= n;
589  return ret;
590 }
591 
592 template <typename T>
593 inline T Vector3<T>::GetNorm() const
594 {
595  return std::sqrt(GetNormSquared());
596 }
597 
598 template <typename T>
600 {
601  return this->Dot(*this);
602 }
603 
604 template <typename T>
605 inline int Vector3<T>::LongestAxis() const
606 {
607  auto it = std::max_element(m_data.begin(), m_data.end());
608  return int(std::distance(m_data.begin(), it));
609 }
610 
611 /*
612  * Vector-vector operations
613  */
614 template <typename T>
616 {
617  GetX() = rhs.GetX();
618  GetY() = rhs.GetY();
619  GetZ() = rhs.GetZ();
620  return *this;
621 }
622 
623 template <typename T>
625 {
626  GetX() += rhs.GetX();
627  GetY() += rhs.GetY();
628  GetZ() += rhs.GetZ();
629  return *this;
630 }
631 
632 template <typename T>
634 {
635  GetX() -= rhs.GetX();
636  GetY() -= rhs.GetY();
637  GetZ() -= rhs.GetZ();
638  return *this;
639 }
640 
641 template <typename T>
643 {
644  return Vector3<T>(GetX() * rhs.GetX(), GetY() * rhs.GetY(), GetZ() * rhs.GetZ());
645 }
646 
647 template <typename T>
648 inline Vector3<T> Vector3<T>::Cross(const Vector3<T>& rhs) const
649 {
650  return Vector3<T>(GetY() * rhs.GetZ() - GetZ() * rhs.GetY(),
651  GetZ() * rhs.GetX() - GetX() * rhs.GetZ(),
652  GetX() * rhs.GetY() - GetY() * rhs.GetX());
653 }
654 
655 template <typename T>
656 inline T Vector3<T>::Dot(const Vector3<T>& rhs) const
657 {
658  return GetX() * rhs.GetX() + GetY() * rhs.GetY() + GetZ() * rhs.GetZ();
659 }
660 
661 template <typename T>
663 {
664  return Vector3<T>(GetX() + rhs.GetX(), GetY() + rhs.GetY(), GetZ() + rhs.GetZ());
665 }
666 
667 template <typename T>
669 {
670  return Vector3<T>(GetX() - rhs.GetX(), GetY() - rhs.GetY(), GetZ() - rhs.GetZ());
671 }
672 
673 template <typename T>
674 inline Vector3<T> operator*(T lhs, const Vector3<T>& rhs)
675 {
676  return Vector3<T>(lhs * rhs.GetX(), lhs * rhs.GetY(), lhs * rhs.GetZ());
677 }
678 
679 /*
680  * Vector-scalar operations
681  */
682 template <typename T>
684 {
685  GetX() -= a;
686  GetY() -= a;
687  GetZ() -= a;
688  return *this;
689 }
690 
691 template <typename T>
693 {
694  GetX() += a;
695  GetY() += a;
696  GetZ() += a;
697  return *this;
698 }
699 
700 template <typename T>
702 {
703  GetX() /= a;
704  GetY() /= a;
705  GetZ() /= a;
706  return *this;
707 }
708 
709 template <typename T>
711 {
712  GetX() *= a;
713  GetY() *= a;
714  GetZ() *= a;
715  return *this;
716 }
717 
718 template <typename T>
720 {
721  return Vector3<T>(GetX() * rhs, GetY() * rhs, GetZ() * rhs);
722 }
723 
724 template <typename T>
726 {
727  return Vector3<T>(GetX() / rhs, GetY() / rhs, GetZ() / rhs);
728 }
729 
730 /*
731  * Unary operations
732  */
733 template <typename T>
735 {
736  return Vector3<T>(-GetX(), -GetY(), -GetZ());
737 }
738 
739 /*
740  * Comparison operators
741  */
742 template <typename T>
743 inline bool Vector3<T>::operator<(const Vector3<T>& rhs) const
744 {
745  if (GetX() == rhs.GetX())
746  {
747  if (GetY() == rhs.GetY())
748  {
749  return (GetZ() < rhs.GetZ());
750  }
751  return (GetY() < rhs.GetY());
752  }
753  return (GetX() < rhs.GetX());
754 }
755 
756 template <typename T>
757 inline bool Vector3<T>::operator>(const Vector3<T>& rhs) const
758 {
759  if (GetX() == rhs.GetX())
760  {
761  if (GetY() == rhs.GetY())
762  {
763  return (GetZ() > rhs.GetZ());
764  }
765  return (GetY() > rhs.GetY());
766  }
767  return (GetX() > rhs.GetZ());
768 }
769 
770 template <typename T>
771 inline bool Vector3<T>::CWiseAllGE(const Vector3<T>& rhs) const
772 {
773  return GetX() >= rhs.GetX() && GetY() >= rhs.GetY() && GetZ() >= rhs.GetZ();
774 }
775 
776 template <typename T>
777 inline bool Vector3<T>::CWiseAllLE(const Vector3<T>& rhs) const
778 {
779  return GetX() <= rhs.GetX() && GetY() <= rhs.GetY() && GetZ() <= rhs.GetZ();
780 }
781 
782 template <typename T>
784 {
785  return Vector3<T>(std::min(GetX(), rhs.GetX()), std::min(GetY(), rhs.GetY()), std::min(GetZ(), rhs.GetZ()));
786 }
787 
788 template <typename T>
790 {
791  return Vector3<T>(std::max(GetX(), rhs.GetX()), std::max(GetY(), rhs.GetY()), std::max(GetZ(), rhs.GetZ()));
792 }
793 
794 template <typename T>
795 inline T Vector3<T>::MinCoeff() const
796 {
797  return *std::min_element(m_data.begin(), m_data.end());
798 }
799 
800 template <typename T>
801 inline T Vector3<T>::MaxCoeff() const
802 {
803  return *std::max_element(m_data.begin(), m_data.end());
804 }
805 
806 template <typename T>
807 inline T Vector3<T>::MinCoeff(uint32_t& idx) const
808 {
809  auto it = std::min_element(m_data.begin(), m_data.end());
810  idx = uint32_t(std::distance(m_data.begin(), it));
811  return *it;
812 }
813 
814 template <typename T>
815 inline T Vector3<T>::MaxCoeff(uint32_t& idx) const
816 {
817  auto it = std::max_element(m_data.begin(), m_data.end());
818  idx = uint32_t(std::distance(m_data.begin(), it));
819  return *it;
820 }
821 
822 /*
823  * Constructors
824  */
825 template <typename T>
826 inline Vector3<T>::Vector3(T a) : m_data{ a, a, a }
827 {
828 }
829 
830 template <typename T>
831 inline Vector3<T>::Vector3(T x, T y, T z) : m_data{ x, y, z }
832 {
833 }
834 
835 template <typename T>
836 inline Vector3<T>::Vector3(const Vector3& rhs) : m_data{ rhs.m_data }
837 {
838 }
839 
840 template <typename T>
841 template <typename U>
842 inline Vector3<T>::Vector3(const Vector3<U>& rhs) : m_data{ T(rhs.GetX()), T(rhs.GetY()), T(rhs.GetZ()) }
843 {
844 }
845 
846 template <typename T>
847 inline Vector3<T>::Vector3(const VHACD::Vertex& rhs) : Vector3<T>(rhs.mX, rhs.mY, rhs.mZ)
848 {
849  static_assert(std::is_same<T, double>::value, "Vertex to Vector3 constructor only enabled for double");
850 }
851 
852 template <typename T>
853 inline Vector3<T>::Vector3(const VHACD::Triangle& rhs) : Vector3<T>(rhs.mI0, rhs.mI1, rhs.mI2)
854 {
855  static_assert(std::is_same<T, uint32_t>::value, "Triangle to Vector3 constructor only enabled for uint32_t");
856 }
857 
858 template <typename T>
860 {
861  static_assert(std::is_same<T, double>::value, "Vector3 to Vertex conversion only enable for double");
862  return ::VHACD::Vertex(GetX(), GetY(), GetZ());
863 }
864 
865 IVHACD* CreateVHACD(); // Create a synchronous (blocking) implementation of V-HACD
866 IVHACD* CreateVHACD_ASYNC(); // Create an asynchronous (non-blocking) implementation of V-HACD
867 
868 } // namespace VHACD
869 
870 #if ENABLE_VHACD_IMPLEMENTATION
871 #include <assert.h>
872 #include <math.h>
873 #include <stdlib.h>
874 #include <string.h>
875 #include <float.h>
876 #include <limits.h>
877 
878 #include <array>
879 #include <atomic>
880 #include <chrono>
881 #include <condition_variable>
882 #include <deque>
883 #include <future>
884 #include <iostream>
885 #include <list>
886 #include <memory>
887 #include <mutex>
888 #include <queue>
889 #include <thread>
890 #include <unordered_map>
891 #include <unordered_set>
892 #include <utility>
893 #include <vector>
894 
895 #ifdef _MSC_VER
896 #pragma warning(push)
897 #pragma warning(disable : 4100 4127 4189 4244 4456 4701 4702 4996)
898 #endif // _MSC_VER
899 
900 #ifdef __GNUC__
901 #pragma GCC diagnostic push
902 // Minimum set of warnings used for cleanup
903 // #pragma GCC diagnostic warning "-Wall"
904 // #pragma GCC diagnostic warning "-Wextra"
905 // #pragma GCC diagnostic warning "-Wpedantic"
906 // #pragma GCC diagnostic warning "-Wold-style-cast"
907 // #pragma GCC diagnostic warning "-Wnon-virtual-dtor"
908 // #pragma GCC diagnostic warning "-Wshadow"
909 #endif // __GNUC__
910 
911 // Scoped Timer
912 namespace VHACD
913 {
914 class Timer
915 {
916 public:
917  Timer() : m_startTime(std::chrono::high_resolution_clock::now()) {}
918 
919  void Reset() { m_startTime = std::chrono::high_resolution_clock::now(); }
920 
921  double GetElapsedSeconds()
922  {
923  auto s = PeekElapsedSeconds();
924  Reset();
925  return s;
926  }
927 
928  double PeekElapsedSeconds()
929  {
930  auto now = std::chrono::high_resolution_clock::now();
931  std::chrono::duration<double> diff = now - m_startTime;
932  return diff.count();
933  }
934 
935 private:
936  std::chrono::time_point<std::chrono::high_resolution_clock> m_startTime;
937 };
938 
939 class ScopedTime
940 {
941 public:
942  ScopedTime(const char* action, VHACD::IVHACD::IUserLogger* logger) : m_action(action), m_logger(logger)
943  {
944  m_timer.Reset();
945  }
946 
947  ~ScopedTime()
948  {
949  double dtime = m_timer.GetElapsedSeconds();
950  if (m_logger)
951  {
952  char scratch[512];
953  snprintf(scratch, sizeof(scratch), "%s took %0.5f seconds", m_action, dtime);
954  m_logger->Log(scratch);
955  }
956  }
957 
958  const char* m_action{ nullptr };
959  Timer m_timer;
960  VHACD::IVHACD::IUserLogger* m_logger{ nullptr };
961 };
962 BoundsAABB::BoundsAABB(const std::vector<VHACD::Vertex>& points) : m_min(points[0]), m_max(points[0])
963 {
964  for (uint32_t i = 1; i < points.size(); ++i)
965  {
966  const VHACD::Vertex& p = points[i];
967  m_min = m_min.CWiseMin(p);
968  m_max = m_max.CWiseMax(p);
969  }
970 }
971 
972 BoundsAABB::BoundsAABB(const VHACD::Vect3& min, const VHACD::Vect3& max) : m_min(min), m_max(max) {}
973 
974 BoundsAABB BoundsAABB::Union(const BoundsAABB& b)
975 {
976  return BoundsAABB(GetMin().CWiseMin(b.GetMin()), GetMax().CWiseMax(b.GetMax()));
977 }
978 
980 {
981  if ((GetMin().GetX() > b.GetMax().GetX()) || (b.GetMin().GetX() > GetMax().GetX()))
982  return false;
983  if ((GetMin().GetY() > b.GetMax().GetY()) || (b.GetMin().GetY() > GetMax().GetY()))
984  return false;
985  if ((GetMin().GetZ() > b.GetMax().GetZ()) || (b.GetMin().GetZ() > GetMax().GetZ()))
986  return false;
987  return true;
988 }
989 
990 double BoundsAABB::SurfaceArea() const
991 {
992  VHACD::Vect3 d = GetMax() - GetMin();
993  return double(2.0) * (d.GetX() * d.GetY() + d.GetX() * d.GetZ() + d.GetY() * d.GetZ());
994 }
995 
996 double VHACD::BoundsAABB::Volume() const
997 {
998  VHACD::Vect3 d = GetMax() - GetMin();
999  return d.GetX() * d.GetY() * d.GetZ();
1000 }
1001 
1002 BoundsAABB VHACD::BoundsAABB::Inflate(double ratio) const
1003 {
1004  double inflate = (GetMin() - GetMax()).GetNorm() * double(0.5) * ratio;
1005  return BoundsAABB(GetMin() - inflate, GetMax() + inflate);
1006 }
1007 
1009 {
1010  return p.CWiseMax(GetMin()).CWiseMin(GetMax());
1011 }
1012 
1013 VHACD::Vect3& VHACD::BoundsAABB::GetMin() { return m_min; }
1014 
1015 VHACD::Vect3& VHACD::BoundsAABB::GetMax() { return m_max; }
1016 
1017 inline const VHACD::Vect3& VHACD::BoundsAABB::GetMin() const { return m_min; }
1018 
1019 const VHACD::Vect3& VHACD::BoundsAABB::GetMax() const { return m_max; }
1020 
1021 VHACD::Vect3 VHACD::BoundsAABB::GetSize() const { return GetMax() - GetMin(); }
1022 
1023 VHACD::Vect3 VHACD::BoundsAABB::GetCenter() const { return (GetMin() + GetMax()) * double(0.5); }
1024 
1025 /*
1026  * Relies on three way comparison, which std::sort doesn't use
1027  */
1028 template <class T, class dCompareKey>
1029 void Sort(T* const array, int elements)
1030 {
1031  const int batchSize = 8;
1032  int stack[1024][2];
1033 
1034  stack[0][0] = 0;
1035  stack[0][1] = elements - 1;
1036  int stackIndex = 1;
1037  const dCompareKey comparator;
1038  while (stackIndex)
1039  {
1040  stackIndex--;
1041  int lo = stack[stackIndex][0];
1042  int hi = stack[stackIndex][1];
1043  if ((hi - lo) > batchSize)
1044  {
1045  int mid = (lo + hi) >> 1;
1046  if (comparator.Compare(array[lo], array[mid]) > 0)
1047  {
1048  std::swap(array[lo], array[mid]);
1049  }
1050  if (comparator.Compare(array[mid], array[hi]) > 0)
1051  {
1052  std::swap(array[mid], array[hi]);
1053  }
1054  if (comparator.Compare(array[lo], array[mid]) > 0)
1055  {
1056  std::swap(array[lo], array[mid]);
1057  }
1058  int i = lo + 1;
1059  int j = hi - 1;
1060  const T pivot(array[mid]);
1061  do
1062  {
1063  while (comparator.Compare(array[i], pivot) < 0)
1064  {
1065  i++;
1066  }
1067  while (comparator.Compare(array[j], pivot) > 0)
1068  {
1069  j--;
1070  }
1071 
1072  if (i <= j)
1073  {
1074  std::swap(array[i], array[j]);
1075  i++;
1076  j--;
1077  }
1078  } while (i <= j);
1079 
1080  if (i < hi)
1081  {
1082  stack[stackIndex][0] = i;
1083  stack[stackIndex][1] = hi;
1084  stackIndex++;
1085  }
1086  if (lo < j)
1087  {
1088  stack[stackIndex][0] = lo;
1089  stack[stackIndex][1] = j;
1090  stackIndex++;
1091  }
1092  assert(stackIndex < int(sizeof(stack) / (2 * sizeof(stack[0][0]))));
1093  }
1094  }
1095 
1096  int stride = batchSize + 1;
1097  if (elements < stride)
1098  {
1099  stride = elements;
1100  }
1101  for (int i = 1; i < stride; ++i)
1102  {
1103  if (comparator.Compare(array[0], array[i]) > 0)
1104  {
1105  std::swap(array[0], array[i]);
1106  }
1107  }
1108 
1109  for (int i = 1; i < elements; ++i)
1110  {
1111  int j = i;
1112  const T tmp(array[i]);
1113  for (; comparator.Compare(array[j - 1], tmp) > 0; --j)
1114  {
1115  assert(j > 0);
1116  array[j] = array[j - 1];
1117  }
1118  array[j] = tmp;
1119  }
1120 }
1121 
1122 /*
1123 Maintaining comment due to attribution
1124 Purpose:
1125 
1126 TRIANGLE_AREA_3D computes the area of a triangle in 3D.
1127 
1128 Modified:
1129 
1130 22 April 1999
1131 
1132 Author:
1133 
1134 John Burkardt
1135 
1136 Parameters:
1137 
1138 Input, double X1, Y1, Z1, X2, Y2, Z2, X3, Y3, Z3, the (getX,getY,getZ)
1139 coordinates of the corners of the triangle.
1140 
1141 Output, double TRIANGLE_AREA_3D, the area of the triangle.
1142 */
1143 double ComputeArea(const VHACD::Vect3& p1, const VHACD::Vect3& p2, const VHACD::Vect3& p3)
1144 {
1145  /*
1146  Find the projection of (P3-P1) onto (P2-P1).
1147  */
1148  double base = (p2 - p1).GetNorm();
1149  /*
1150  The height of the triangle is the length of (P3-P1) after its
1151  projection onto (P2-P1) has been subtracted.
1152  */
1153  double height;
1154  if (base == double(0.0))
1155  {
1156  height = double(0.0);
1157  }
1158  else
1159  {
1160  double dot = (p3 - p1).Dot(p2 - p1);
1161  double alpha = dot / (base * base);
1162 
1163  VHACD::Vect3 a = p3 - p1 - alpha * (p2 - p1);
1164  height = a.GetNorm();
1165  }
1166 
1167  return double(0.5) * base * height;
1168 }
1169 
1170 bool ComputeCentroid(const std::vector<VHACD::Vertex>& points,
1171  const std::vector<VHACD::Triangle>& indices,
1172  VHACD::Vect3& center)
1173 
1174 {
1175  bool ret = false;
1176  if (points.size())
1177  {
1178  center = VHACD::Vect3(0);
1179 
1180  VHACD::Vect3 numerator(0);
1181  double denominator = 0;
1182 
1183  for (uint32_t i = 0; i < indices.size(); i++)
1184  {
1185  uint32_t i1 = indices[i].mI0;
1186  uint32_t i2 = indices[i].mI1;
1187  uint32_t i3 = indices[i].mI2;
1188 
1189  const VHACD::Vect3& p1 = points[i1];
1190  const VHACD::Vect3& p2 = points[i2];
1191  const VHACD::Vect3& p3 = points[i3];
1192 
1193  // Compute the average of the sum of the three positions
1194  VHACD::Vect3 sum = (p1 + p2 + p3) / 3;
1195 
1196  // Compute the area of this triangle
1197  double area = ComputeArea(p1, p2, p3);
1198 
1199  numerator += (sum * area);
1200 
1201  denominator += area;
1202  }
1203  double recip = 1 / denominator;
1204  center = numerator * recip;
1205  ret = true;
1206  }
1207  return ret;
1208 }
1209 
1210 double Determinant3x3(const std::array<VHACD::Vect3, 3>& matrix, double& error)
1211 {
1212  double det = double(0.0);
1213  error = double(0.0);
1214 
1215  double a01xa12 = matrix[0].GetY() * matrix[1].GetZ();
1216  double a02xa11 = matrix[0].GetZ() * matrix[1].GetY();
1217  error += (std::abs(a01xa12) + std::abs(a02xa11)) * std::abs(matrix[2].GetX());
1218  det += (a01xa12 - a02xa11) * matrix[2].GetX();
1219 
1220  double a00xa12 = matrix[0].GetX() * matrix[1].GetZ();
1221  double a02xa10 = matrix[0].GetZ() * matrix[1].GetX();
1222  error += (std::abs(a00xa12) + std::abs(a02xa10)) * std::abs(matrix[2].GetY());
1223  det -= (a00xa12 - a02xa10) * matrix[2].GetY();
1224 
1225  double a00xa11 = matrix[0].GetX() * matrix[1].GetY();
1226  double a01xa10 = matrix[0].GetY() * matrix[1].GetX();
1227  error += (std::abs(a00xa11) + std::abs(a01xa10)) * std::abs(matrix[2].GetZ());
1228  det += (a00xa11 - a01xa10) * matrix[2].GetZ();
1229 
1230  return det;
1231 }
1232 
1233 double ComputeMeshVolume(const std::vector<VHACD::Vertex>& vertices, const std::vector<VHACD::Triangle>& indices)
1234 {
1235  double volume = 0;
1236  for (uint32_t i = 0; i < indices.size(); i++)
1237  {
1238  const std::array<VHACD::Vect3, 3> m = { vertices[indices[i].mI0],
1239  vertices[indices[i].mI1],
1240  vertices[indices[i].mI2] };
1241  double placeholder;
1242  volume += Determinant3x3(m, placeholder);
1243  }
1244 
1245  volume *= (double(1.0) / double(6.0));
1246  if (volume < 0)
1247  volume *= -1;
1248  return volume;
1249 }
1250 
1251 /*
1252  * To minimize memory allocations while maintaining pointer stability.
1253  * Used in KdTreeNode and ConvexHull, as both use tree data structures that rely on pointer stability
1254  * Neither rely on random access or iteration
1255  * They just dump elements into a memory pool, then refer to pointers to the elements
1256  * All elements are default constructed in NodeStorage's m_nodes array
1257  */
1258 template <typename T, std::size_t MaxBundleSize = 1024>
1259 class NodeBundle
1260 {
1261  struct NodeStorage
1262  {
1263  bool IsFull() const;
1264 
1265  T& GetNextNode();
1266 
1267  std::size_t m_index;
1268  std::array<T, MaxBundleSize> m_nodes;
1269  };
1270 
1271  std::list<NodeStorage> m_list;
1272  typename std::list<NodeStorage>::iterator m_head{ m_list.end() };
1273 
1274 public:
1275  T& GetNextNode();
1276 
1277  T& GetFirstNode();
1278 
1279  void Clear();
1280 };
1281 
1282 template <typename T, std::size_t MaxBundleSize>
1283 bool NodeBundle<T, MaxBundleSize>::NodeStorage::IsFull() const
1284 {
1285  return m_index == MaxBundleSize;
1286 }
1287 
1288 template <typename T, std::size_t MaxBundleSize>
1289 T& NodeBundle<T, MaxBundleSize>::NodeStorage::GetNextNode()
1290 {
1291  assert(m_index < MaxBundleSize);
1292  T& ret = m_nodes[m_index];
1293  m_index++;
1294  return ret;
1295 }
1296 
1297 template <typename T, std::size_t MaxBundleSize>
1298 T& NodeBundle<T, MaxBundleSize>::GetNextNode()
1299 {
1300  /*
1301  * || short circuits, so doesn't dereference if m_bundle == m_bundleHead.end()
1302  */
1303  if (m_head == m_list.end() || m_head->IsFull())
1304  {
1305  m_head = m_list.emplace(m_list.end());
1306  }
1307 
1308  return m_head->GetNextNode();
1309 }
1310 
1311 template <typename T, std::size_t MaxBundleSize>
1312 T& NodeBundle<T, MaxBundleSize>::GetFirstNode()
1313 {
1314  assert(m_head != m_list.end());
1315  return m_list.front().m_nodes[0];
1316 }
1317 
1318 template <typename T, std::size_t MaxBundleSize>
1319 void NodeBundle<T, MaxBundleSize>::Clear()
1320 {
1321  m_list.clear();
1322 }
1323 
1324 /*
1325  * Returns index of highest set bit in x
1326  */
1327 inline int dExp2(int x)
1328 {
1329  int exp;
1330  for (exp = -1; x; x >>= 1)
1331  {
1332  exp++;
1333  }
1334  return exp;
1335 }
1336 
1337 /*
1338  * Reverses the order of the bits in v and returns the result
1339  * Does not put fill any of the bits higher than the highest bit in v
1340  * Only used to calculate index of ndNormalMap::m_normal when tessellating a triangle
1341  */
1342 inline int dBitReversal(int v, int base)
1343 {
1344  int x = 0;
1345  int power = dExp2(base) - 1;
1346  do
1347  {
1348  x += (v & 1) << power;
1349  v >>= 1;
1350  power--;
1351  } while (v);
1352  return x;
1353 }
1354 
1355 class Googol
1356 {
1357 #define VHACD_GOOGOL_SIZE 4
1358 public:
1359  Googol() = default;
1360  Googol(double value);
1361 
1362  operator double() const;
1363  Googol operator+(const Googol& A) const;
1364  Googol operator-(const Googol& A) const;
1365  Googol operator*(const Googol& A) const;
1366  Googol operator/(const Googol& A) const;
1367 
1368  Googol& operator+=(const Googol& A);
1369  Googol& operator-=(const Googol& A);
1370 
1371  bool operator>(const Googol& A) const;
1372  bool operator>=(const Googol& A) const;
1373  bool operator<(const Googol& A) const;
1374  bool operator<=(const Googol& A) const;
1375  bool operator==(const Googol& A) const;
1376  bool operator!=(const Googol& A) const;
1377 
1378  Googol Abs() const;
1379  Googol Floor() const;
1380  Googol InvSqrt() const;
1381  Googol Sqrt() const;
1382 
1383  void ToString(char* const string) const;
1384 
1385 private:
1386  void NegateMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa) const;
1387  void CopySignedMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa) const;
1388  int NormalizeMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa) const;
1389  void ShiftRightMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa, int bits) const;
1390  uint64_t CheckCarrier(uint64_t a, uint64_t b) const;
1391 
1392  int LeadingZeros(uint64_t a) const;
1393  void ExtendedMultiply(uint64_t a, uint64_t b, uint64_t& high, uint64_t& low) const;
1394  void ScaleMantissa(uint64_t* out, uint64_t scale) const;
1395 
1396  int m_sign{ 0 };
1397  int m_exponent{ 0 };
1398  std::array<uint64_t, VHACD_GOOGOL_SIZE> m_mantissa{ 0 };
1399 
1400 public:
1401  static Googol m_zero;
1402  static Googol m_one;
1403  static Googol m_two;
1404  static Googol m_three;
1405  static Googol m_half;
1406 };
1407 
1408 Googol Googol::m_zero(double(0.0));
1409 Googol Googol::m_one(double(1.0));
1410 Googol Googol::m_two(double(2.0));
1411 Googol Googol::m_three(double(3.0));
1412 Googol Googol::m_half(double(0.5));
1413 
1414 Googol::Googol(double value)
1415 {
1416  int exp;
1417  double mantissa = fabs(frexp(value, &exp));
1418 
1419  m_exponent = exp;
1420  m_sign = (value >= 0) ? 0 : 1;
1421 
1422  m_mantissa[0] = uint64_t(double(uint64_t(1) << 62) * mantissa);
1423 }
1424 
1425 Googol::operator double() const
1426 {
1427  double mantissa = (double(1.0) / double(uint64_t(1) << 62)) * double(m_mantissa[0]);
1428  mantissa = ldexp(mantissa, m_exponent) * (m_sign ? double(-1.0) : double(1.0));
1429  return mantissa;
1430 }
1431 
1432 Googol Googol::operator+(const Googol& A) const
1433 {
1434  Googol tmp;
1435  if (m_mantissa[0] && A.m_mantissa[0])
1436  {
1437  std::array<uint64_t, VHACD_GOOGOL_SIZE> mantissa0;
1438  std::array<uint64_t, VHACD_GOOGOL_SIZE> mantissa1;
1439  std::array<uint64_t, VHACD_GOOGOL_SIZE> mantissa;
1440 
1441  CopySignedMantissa(mantissa0);
1442  A.CopySignedMantissa(mantissa1);
1443 
1444  int exponentDiff = m_exponent - A.m_exponent;
1445  int exponent = m_exponent;
1446  if (exponentDiff > 0)
1447  {
1448  ShiftRightMantissa(mantissa1, exponentDiff);
1449  }
1450  else if (exponentDiff < 0)
1451  {
1452  exponent = A.m_exponent;
1453  ShiftRightMantissa(mantissa0, -exponentDiff);
1454  }
1455 
1456  uint64_t carrier = 0;
1457  for (int i = VHACD_GOOGOL_SIZE - 1; i >= 0; i--)
1458  {
1459  uint64_t m0 = mantissa0[i];
1460  uint64_t m1 = mantissa1[i];
1461  mantissa[i] = m0 + m1 + carrier;
1462  carrier = CheckCarrier(m0, m1) | CheckCarrier(m0 + m1, carrier);
1463  }
1464 
1465  int sign = 0;
1466  if (int64_t(mantissa[0]) < 0)
1467  {
1468  sign = 1;
1469  NegateMantissa(mantissa);
1470  }
1471 
1472  int bits = NormalizeMantissa(mantissa);
1473  if (bits <= (-64 * VHACD_GOOGOL_SIZE))
1474  {
1475  tmp.m_sign = 0;
1476  tmp.m_exponent = 0;
1477  }
1478  else
1479  {
1480  tmp.m_sign = sign;
1481  tmp.m_exponent = int(exponent + bits);
1482  }
1483 
1484  tmp.m_mantissa = mantissa;
1485  }
1486  else if (A.m_mantissa[0])
1487  {
1488  tmp = A;
1489  }
1490  else
1491  {
1492  tmp = *this;
1493  }
1494 
1495  return tmp;
1496 }
1497 
1498 Googol Googol::operator-(const Googol& A) const
1499 {
1500  Googol tmp(A);
1501  tmp.m_sign = !tmp.m_sign;
1502  return *this + tmp;
1503 }
1504 
1505 Googol Googol::operator*(const Googol& A) const
1506 {
1507  if (m_mantissa[0] && A.m_mantissa[0])
1508  {
1509  std::array<uint64_t, VHACD_GOOGOL_SIZE * 2> mantissaAcc{ 0 };
1510  for (int i = VHACD_GOOGOL_SIZE - 1; i >= 0; i--)
1511  {
1512  uint64_t a = m_mantissa[i];
1513  if (a)
1514  {
1515  uint64_t mantissaScale[2 * VHACD_GOOGOL_SIZE] = { 0 };
1516  A.ScaleMantissa(&mantissaScale[i], a);
1517 
1518  uint64_t carrier = 0;
1519  for (int j = 0; j < 2 * VHACD_GOOGOL_SIZE; j++)
1520  {
1521  const int k = 2 * VHACD_GOOGOL_SIZE - 1 - j;
1522  uint64_t m0 = mantissaAcc[k];
1523  uint64_t m1 = mantissaScale[k];
1524  mantissaAcc[k] = m0 + m1 + carrier;
1525  carrier = CheckCarrier(m0, m1) | CheckCarrier(m0 + m1, carrier);
1526  }
1527  }
1528  }
1529 
1530  uint64_t carrier = 0;
1531  int bits = LeadingZeros(mantissaAcc[0]) - 2;
1532  for (int i = 0; i < 2 * VHACD_GOOGOL_SIZE; i++)
1533  {
1534  const int k = 2 * VHACD_GOOGOL_SIZE - 1 - i;
1535  uint64_t a = mantissaAcc[k];
1536  mantissaAcc[k] = (a << uint64_t(bits)) | carrier;
1537  carrier = a >> uint64_t(64 - bits);
1538  }
1539 
1540  int exp = m_exponent + A.m_exponent - (bits - 2);
1541 
1542  Googol tmp;
1543  tmp.m_sign = m_sign ^ A.m_sign;
1544  tmp.m_exponent = exp;
1545  for (std::size_t i = 0; i < tmp.m_mantissa.size(); ++i)
1546  {
1547  tmp.m_mantissa[i] = mantissaAcc[i];
1548  }
1549 
1550  return tmp;
1551  }
1552  return Googol(double(0.0));
1553 }
1554 
1555 Googol Googol::operator/(const Googol& A) const
1556 {
1557  Googol tmp(double(1.0) / A);
1558  tmp = tmp * (m_two - A * tmp);
1559  tmp = tmp * (m_two - A * tmp);
1560  bool test = false;
1561  int passes = 0;
1562  do
1563  {
1564  passes++;
1565  Googol tmp0(tmp);
1566  tmp = tmp * (m_two - A * tmp);
1567  test = tmp0 == tmp;
1568  } while (test && (passes < (2 * VHACD_GOOGOL_SIZE)));
1569  return (*this) * tmp;
1570 }
1571 
1572 Googol& Googol::operator+=(const Googol& A)
1573 {
1574  *this = *this + A;
1575  return *this;
1576 }
1577 
1578 Googol& Googol::operator-=(const Googol& A)
1579 {
1580  *this = *this - A;
1581  return *this;
1582 }
1583 
1584 bool Googol::operator>(const Googol& A) const
1585 {
1586  Googol tmp(*this - A);
1587  return double(tmp) > double(0.0);
1588 }
1589 
1590 bool Googol::operator>=(const Googol& A) const
1591 {
1592  Googol tmp(*this - A);
1593  return double(tmp) >= double(0.0);
1594 }
1595 
1596 bool Googol::operator<(const Googol& A) const
1597 {
1598  Googol tmp(*this - A);
1599  return double(tmp) < double(0.0);
1600 }
1601 
1602 bool Googol::operator<=(const Googol& A) const
1603 {
1604  Googol tmp(*this - A);
1605  return double(tmp) <= double(0.0);
1606 }
1607 
1608 bool Googol::operator==(const Googol& A) const
1609 {
1610  return m_sign == A.m_sign && m_exponent == A.m_exponent && m_mantissa == A.m_mantissa;
1611 }
1612 
1613 bool Googol::operator!=(const Googol& A) const { return !(*this == A); }
1614 
1615 Googol Googol::Abs() const
1616 {
1617  Googol tmp(*this);
1618  tmp.m_sign = 0;
1619  return tmp;
1620 }
1621 
1622 Googol Googol::Floor() const
1623 {
1624  if (m_exponent < 1)
1625  {
1626  return Googol(double(0.0));
1627  }
1628  int bits = m_exponent + 2;
1629  int start = 0;
1630  while (bits >= 64)
1631  {
1632  bits -= 64;
1633  start++;
1634  }
1635 
1636  Googol tmp(*this);
1637  for (int i = VHACD_GOOGOL_SIZE - 1; i > start; i--)
1638  {
1639  tmp.m_mantissa[i] = 0;
1640  }
1641  // some compilers do no like this and I do not know why is that
1642  // uint64_t mask = (-1LL) << (64 - bits);
1643  uint64_t mask(~0ULL);
1644  mask <<= (64 - bits);
1645  tmp.m_mantissa[start] &= mask;
1646  return tmp;
1647 }
1648 
1649 Googol Googol::InvSqrt() const
1650 {
1651  const Googol& me = *this;
1652  Googol x(double(1.0) / sqrt(me));
1653 
1654  int test = 0;
1655  int passes = 0;
1656  do
1657  {
1658  passes++;
1659  Googol tmp(x);
1660  x = m_half * x * (m_three - me * x * x);
1661  test = (x != tmp);
1662  } while (test && (passes < (2 * VHACD_GOOGOL_SIZE)));
1663  return x;
1664 }
1665 
1666 Googol Googol::Sqrt() const { return *this * InvSqrt(); }
1667 
1668 void Googol::ToString(char* const string) const
1669 {
1670  Googol tmp(*this);
1671  Googol base(double(10.0));
1672  while (double(tmp) > double(1.0))
1673  {
1674  tmp = tmp / base;
1675  }
1676 
1677  int index = 0;
1678  while (tmp.m_mantissa[0])
1679  {
1680  tmp = tmp * base;
1681  Googol digit(tmp.Floor());
1682  tmp -= digit;
1683  double val = digit;
1684  string[index] = char(val) + '0';
1685  index++;
1686  }
1687  string[index] = 0;
1688 }
1689 
1690 void Googol::NegateMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa) const
1691 {
1692  uint64_t carrier = 1;
1693  for (size_t i = mantissa.size() - 1; i < mantissa.size(); i--)
1694  {
1695  uint64_t a = ~mantissa[i] + carrier;
1696  if (a)
1697  {
1698  carrier = 0;
1699  }
1700  mantissa[i] = a;
1701  }
1702 }
1703 
1704 void Googol::CopySignedMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa) const
1705 {
1706  mantissa = m_mantissa;
1707  if (m_sign)
1708  {
1709  NegateMantissa(mantissa);
1710  }
1711 }
1712 
1713 int Googol::NormalizeMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa) const
1714 {
1715  int bits = 0;
1716  if (int64_t(mantissa[0] * 2) < 0)
1717  {
1718  bits = 1;
1719  ShiftRightMantissa(mantissa, 1);
1720  }
1721  else
1722  {
1723  while (!mantissa[0] && bits > (-64 * VHACD_GOOGOL_SIZE))
1724  {
1725  bits -= 64;
1726  for (int i = 1; i < VHACD_GOOGOL_SIZE; i++)
1727  {
1728  mantissa[i - 1] = mantissa[i];
1729  }
1730  mantissa[VHACD_GOOGOL_SIZE - 1] = 0;
1731  }
1732 
1733  if (bits > (-64 * VHACD_GOOGOL_SIZE))
1734  {
1735  int n = LeadingZeros(mantissa[0]) - 2;
1736  if (n > 0)
1737  {
1738  uint64_t carrier = 0;
1739  for (int i = VHACD_GOOGOL_SIZE - 1; i >= 0; i--)
1740  {
1741  uint64_t a = mantissa[i];
1742  mantissa[i] = (a << n) | carrier;
1743  carrier = a >> (64 - n);
1744  }
1745  bits -= n;
1746  }
1747  else if (n < 0)
1748  {
1749  // this is very rare but it does happens, whee the leading zeros of the mantissa is an exact multiple of 64
1750  uint64_t carrier = 0;
1751  int shift = -n;
1752  for (int i = 0; i < VHACD_GOOGOL_SIZE; i++)
1753  {
1754  uint64_t a = mantissa[i];
1755  mantissa[i] = (a >> shift) | carrier;
1756  carrier = a << (64 - shift);
1757  }
1758  bits -= n;
1759  }
1760  }
1761  }
1762  return bits;
1763 }
1764 
1765 void Googol::ShiftRightMantissa(std::array<uint64_t, VHACD_GOOGOL_SIZE>& mantissa, int bits) const
1766 {
1767  uint64_t carrier = 0;
1768  if (int64_t(mantissa[0]) < int64_t(0))
1769  {
1770  carrier = uint64_t(-1);
1771  }
1772 
1773  while (bits >= 64)
1774  {
1775  for (int i = VHACD_GOOGOL_SIZE - 2; i >= 0; i--)
1776  {
1777  mantissa[i + 1] = mantissa[i];
1778  }
1779  mantissa[0] = carrier;
1780  bits -= 64;
1781  }
1782 
1783  if (bits > 0)
1784  {
1785  carrier <<= (64 - bits);
1786  for (int i = 0; i < VHACD_GOOGOL_SIZE; i++)
1787  {
1788  uint64_t a = mantissa[i];
1789  mantissa[i] = (a >> bits) | carrier;
1790  carrier = a << (64 - bits);
1791  }
1792  }
1793 }
1794 
1795 uint64_t Googol::CheckCarrier(uint64_t a, uint64_t b) const { return ((uint64_t(-1) - b) < a) ? uint64_t(1) : 0; }
1796 
1797 int Googol::LeadingZeros(uint64_t a) const
1798 {
1799 #define VHACD_COUNTBIT(mask, add) \
1800  do \
1801  { \
1802  uint64_t test = a & mask; \
1803  n += test ? 0 : add; \
1804  a = test ? test : (a & ~mask); \
1805  } while (false)
1806 
1807  int n = 0;
1808  VHACD_COUNTBIT(0xffffffff00000000LL, 32);
1809  VHACD_COUNTBIT(0xffff0000ffff0000LL, 16);
1810  VHACD_COUNTBIT(0xff00ff00ff00ff00LL, 8);
1811  VHACD_COUNTBIT(0xf0f0f0f0f0f0f0f0LL, 4);
1812  VHACD_COUNTBIT(0xccccccccccccccccLL, 2);
1813  VHACD_COUNTBIT(0xaaaaaaaaaaaaaaaaLL, 1);
1814 
1815  return n;
1816 }
1817 
1818 void Googol::ExtendedMultiply(uint64_t a, uint64_t b, uint64_t& high, uint64_t& low) const
1819 {
1820  uint64_t bLow = b & 0xffffffff;
1821  uint64_t bHigh = b >> 32;
1822  uint64_t aLow = a & 0xffffffff;
1823  uint64_t aHigh = a >> 32;
1824 
1825  uint64_t l = bLow * aLow;
1826 
1827  uint64_t c1 = bHigh * aLow;
1828  uint64_t c2 = bLow * aHigh;
1829  uint64_t m = c1 + c2;
1830  uint64_t carrier = CheckCarrier(c1, c2) << 32;
1831 
1832  uint64_t h = bHigh * aHigh + carrier;
1833 
1834  uint64_t ml = m << 32;
1835  uint64_t ll = l + ml;
1836  uint64_t mh = (m >> 32) + CheckCarrier(l, ml);
1837  uint64_t hh = h + mh;
1838 
1839  low = ll;
1840  high = hh;
1841 }
1842 
1843 void Googol::ScaleMantissa(uint64_t* dst, uint64_t scale) const
1844 {
1845  uint64_t carrier = 0;
1846  for (int i = VHACD_GOOGOL_SIZE - 1; i >= 0; i--)
1847  {
1848  if (m_mantissa[i])
1849  {
1850  uint64_t low;
1851  uint64_t high;
1852  ExtendedMultiply(scale, m_mantissa[i], high, low);
1853  uint64_t acc = low + carrier;
1854  carrier = CheckCarrier(low, carrier);
1855  carrier += high;
1856  dst[i + 1] = acc;
1857  }
1858  else
1859  {
1860  dst[i + 1] = carrier;
1861  carrier = 0;
1862  }
1863  }
1864  dst[0] = carrier;
1865 }
1866 
1867 Googol Determinant3x3(const std::array<VHACD::Vector3<Googol>, 3>& matrix)
1868 {
1869  Googol det = double(0.0);
1870 
1871  Googol a01xa12 = matrix[0].GetY() * matrix[1].GetZ();
1872  Googol a02xa11 = matrix[0].GetZ() * matrix[1].GetY();
1873  det += (a01xa12 - a02xa11) * matrix[2].GetX();
1874 
1875  Googol a00xa12 = matrix[0].GetX() * matrix[1].GetZ();
1876  Googol a02xa10 = matrix[0].GetZ() * matrix[1].GetX();
1877  det -= (a00xa12 - a02xa10) * matrix[2].GetY();
1878 
1879  Googol a00xa11 = matrix[0].GetX() * matrix[1].GetY();
1880  Googol a01xa10 = matrix[0].GetY() * matrix[1].GetX();
1881  det += (a00xa11 - a01xa10) * matrix[2].GetZ();
1882  return det;
1883 }
1884 
1885 class HullPlane : public VHACD::Vect3
1886 {
1887 public:
1888  HullPlane(const HullPlane&) = default;
1889  HullPlane(double x, double y, double z, double w);
1890 
1891  HullPlane(const VHACD::Vect3& p, double w);
1892 
1893  HullPlane(const VHACD::Vect3& p0, const VHACD::Vect3& p1, const VHACD::Vect3& p2);
1894 
1895  HullPlane Scale(double s) const;
1896 
1897  HullPlane& operator=(const HullPlane& rhs);
1898 
1899  double Evalue(const VHACD::Vect3& point) const;
1900 
1901  double& GetW();
1902  const double& GetW() const;
1903 
1904 private:
1905  double m_w;
1906 };
1907 
1908 HullPlane::HullPlane(double x, double y, double z, double w) : VHACD::Vect3(x, y, z), m_w(w) {}
1909 
1910 HullPlane::HullPlane(const VHACD::Vect3& p, double w) : VHACD::Vect3(p), m_w(w) {}
1911 
1912 HullPlane::HullPlane(const VHACD::Vect3& p0, const VHACD::Vect3& p1, const VHACD::Vect3& p2)
1913  : VHACD::Vect3((p1 - p0).Cross(p2 - p0)), m_w(-Dot(p0))
1914 {
1915 }
1916 
1917 HullPlane HullPlane::Scale(double s) const { return HullPlane(*this * s, m_w * s); }
1918 
1919 HullPlane& HullPlane::operator=(const HullPlane& rhs)
1920 {
1921  GetX() = rhs.GetX();
1922  GetY() = rhs.GetY();
1923  GetZ() = rhs.GetZ();
1924  m_w = rhs.m_w;
1925  return *this;
1926 }
1927 
1928 double HullPlane::Evalue(const VHACD::Vect3& point) const { return Dot(point) + m_w; }
1929 
1930 double& HullPlane::GetW() { return m_w; }
1931 
1932 const double& HullPlane::GetW() const { return m_w; }
1933 
1934 class ConvexHullFace
1935 {
1936 public:
1937  ConvexHullFace() = default;
1938  double Evalue(const std::vector<VHACD::Vect3>& pointArray, const VHACD::Vect3& point) const;
1939  HullPlane GetPlaneEquation(const std::vector<VHACD::Vect3>& pointArray, bool& isValid) const;
1940 
1941  std::array<int, 3> m_index;
1942 
1943 private:
1944  int m_mark{ 0 };
1945  std::array<std::list<ConvexHullFace>::iterator, 3> m_twin;
1946 
1947  friend class ConvexHull;
1948 };
1949 
1950 double ConvexHullFace::Evalue(const std::vector<VHACD::Vect3>& pointArray, const VHACD::Vect3& point) const
1951 {
1952  const VHACD::Vect3& p0 = pointArray[m_index[0]];
1953  const VHACD::Vect3& p1 = pointArray[m_index[1]];
1954  const VHACD::Vect3& p2 = pointArray[m_index[2]];
1955 
1956  std::array<VHACD::Vect3, 3> matrix = { p2 - p0, p1 - p0, point - p0 };
1957  double error;
1958  double det = Determinant3x3(matrix, error);
1959 
1960  // the code use double, however the threshold for accuracy test is the machine precision of a float.
1961  // by changing this to a smaller number, the code should run faster since many small test will be considered valid
1962  // the precision must be a power of two no smaller than the machine precision of a double, (1<<48)
1963  // float64(1<<30) can be a good value
1964 
1965  // double precision = double (1.0f) / double (1<<30);
1966  double precision = double(1.0) / double(1 << 24);
1967  double errbound = error * precision;
1968  if (fabs(det) > errbound)
1969  {
1970  return det;
1971  }
1972 
1973  const VHACD::Vector3<Googol> p0g = pointArray[m_index[0]];
1974  const VHACD::Vector3<Googol> p1g = pointArray[m_index[1]];
1975  const VHACD::Vector3<Googol> p2g = pointArray[m_index[2]];
1976  const VHACD::Vector3<Googol> pointg = point;
1977  std::array<VHACD::Vector3<Googol>, 3> exactMatrix = { p2g - p0g, p1g - p0g, pointg - p0g };
1978  return Determinant3x3(exactMatrix);
1979 }
1980 
1981 HullPlane ConvexHullFace::GetPlaneEquation(const std::vector<VHACD::Vect3>& pointArray, bool& isvalid) const
1982 {
1983  const VHACD::Vect3& p0 = pointArray[m_index[0]];
1984  const VHACD::Vect3& p1 = pointArray[m_index[1]];
1985  const VHACD::Vect3& p2 = pointArray[m_index[2]];
1986  HullPlane plane(p0, p1, p2);
1987 
1988  isvalid = false;
1989  double mag2 = plane.Dot(plane);
1990  if (mag2 > double(1.0e-16))
1991  {
1992  isvalid = true;
1993  plane = plane.Scale(double(1.0) / sqrt(mag2));
1994  }
1995  return plane;
1996 }
1997 
1998 class ConvexHullVertex : public VHACD::Vect3
1999 {
2000 public:
2001  ConvexHullVertex() = default;
2002  ConvexHullVertex(const ConvexHullVertex&) = default;
2003  ConvexHullVertex& operator=(const ConvexHullVertex& rhs) = default;
2004  using VHACD::Vect3::operator=;
2005 
2006  int m_mark{ 0 };
2007 };
2008 
2009 class ConvexHullAABBTreeNode
2010 {
2011 #define VHACD_CONVEXHULL_3D_VERTEX_CLUSTER_SIZE 8
2012 public:
2013  ConvexHullAABBTreeNode() = default;
2014  ConvexHullAABBTreeNode(ConvexHullAABBTreeNode* parent);
2015 
2016  VHACD::Vect3 m_box[2];
2017  ConvexHullAABBTreeNode* m_left{ nullptr };
2018  ConvexHullAABBTreeNode* m_right{ nullptr };
2019  ConvexHullAABBTreeNode* m_parent{ nullptr };
2020 
2021  size_t m_count;
2022  std::array<size_t, VHACD_CONVEXHULL_3D_VERTEX_CLUSTER_SIZE> m_indices;
2023 };
2024 
2025 ConvexHullAABBTreeNode::ConvexHullAABBTreeNode(ConvexHullAABBTreeNode* parent) : m_parent(parent) {}
2026 
2027 class ConvexHull
2028 {
2029  class ndNormalMap;
2030 
2031 public:
2032  ConvexHull(const ConvexHull& source);
2033  ConvexHull(const std::vector<::VHACD::Vertex>& vertexCloud, double distTol, int maxVertexCount = 0x7fffffff);
2034  ~ConvexHull() = default;
2035 
2036  const std::vector<VHACD::Vect3>& GetVertexPool() const;
2037 
2038  const std::list<ConvexHullFace>& GetList() const { return m_list; }
2039 
2040 private:
2041  void BuildHull(const std::vector<::VHACD::Vertex>& vertexCloud, double distTol, int maxVertexCount);
2042 
2043  void GetUniquePoints(std::vector<ConvexHullVertex>& points);
2044  int InitVertexArray(std::vector<ConvexHullVertex>& points, NodeBundle<ConvexHullAABBTreeNode>& memoryPool);
2045 
2046  ConvexHullAABBTreeNode* BuildTreeNew(std::vector<ConvexHullVertex>& points,
2047  std::vector<ConvexHullAABBTreeNode>& memoryPool) const;
2048  ConvexHullAABBTreeNode* BuildTreeOld(std::vector<ConvexHullVertex>& points,
2049  NodeBundle<ConvexHullAABBTreeNode>& memoryPool);
2050  ConvexHullAABBTreeNode* BuildTreeRecurse(ConvexHullAABBTreeNode* const parent,
2051  ConvexHullVertex* const points,
2052  int count,
2053  int baseIndex,
2054  NodeBundle<ConvexHullAABBTreeNode>& memoryPool) const;
2055 
2056  std::list<ConvexHullFace>::iterator AddFace(int i0, int i1, int i2);
2057 
2058  void CalculateConvexHull3D(ConvexHullAABBTreeNode* vertexTree,
2059  std::vector<ConvexHullVertex>& points,
2060  int count,
2061  double distTol,
2062  int maxVertexCount);
2063 
2064  int SupportVertex(ConvexHullAABBTreeNode** const tree,
2065  const std::vector<ConvexHullVertex>& points,
2066  const VHACD::Vect3& dir,
2067  const bool removeEntry = true) const;
2068  double TetrahedrumVolume(const VHACD::Vect3& p0,
2069  const VHACD::Vect3& p1,
2070  const VHACD::Vect3& p2,
2071  const VHACD::Vect3& p3) const;
2072 
2073  std::list<ConvexHullFace> m_list;
2074  VHACD::Vect3 m_aabbP0{ 0 };
2075  VHACD::Vect3 m_aabbP1{ 0 };
2076  double m_diag{ 0.0 };
2077  std::vector<VHACD::Vect3> m_points;
2078 };
2079 
2080 class ConvexHull::ndNormalMap
2081 {
2082 public:
2083  ndNormalMap();
2084 
2085  static const ndNormalMap& GetNormalMap();
2086 
2087  void
2088  TessellateTriangle(int level, const VHACD::Vect3& p0, const VHACD::Vect3& p1, const VHACD::Vect3& p2, int& count);
2089 
2090  std::array<VHACD::Vect3, 128> m_normal;
2091  int m_count{ 128 };
2092 };
2093 
2094 const ConvexHull::ndNormalMap& ConvexHull::ndNormalMap::GetNormalMap()
2095 {
2096  static ndNormalMap normalMap;
2097  return normalMap;
2098 }
2099 
2100 void ConvexHull::ndNormalMap::TessellateTriangle(int level,
2101  const VHACD::Vect3& p0,
2102  const VHACD::Vect3& p1,
2103  const VHACD::Vect3& p2,
2104  int& count)
2105 {
2106  if (level)
2107  {
2108  assert(fabs(p0.Dot(p0) - double(1.0)) < double(1.0e-4));
2109  assert(fabs(p1.Dot(p1) - double(1.0)) < double(1.0e-4));
2110  assert(fabs(p2.Dot(p2) - double(1.0)) < double(1.0e-4));
2111  VHACD::Vect3 p01(p0 + p1);
2112  VHACD::Vect3 p12(p1 + p2);
2113  VHACD::Vect3 p20(p2 + p0);
2114 
2115  p01 = p01 * (double(1.0) / p01.GetNorm());
2116  p12 = p12 * (double(1.0) / p12.GetNorm());
2117  p20 = p20 * (double(1.0) / p20.GetNorm());
2118 
2119  assert(fabs(p01.GetNormSquared() - double(1.0)) < double(1.0e-4));
2120  assert(fabs(p12.GetNormSquared() - double(1.0)) < double(1.0e-4));
2121  assert(fabs(p20.GetNormSquared() - double(1.0)) < double(1.0e-4));
2122 
2123  TessellateTriangle(level - 1, p0, p01, p20, count);
2124  TessellateTriangle(level - 1, p1, p12, p01, count);
2125  TessellateTriangle(level - 1, p2, p20, p12, count);
2126  TessellateTriangle(level - 1, p01, p12, p20, count);
2127  }
2128  else
2129  {
2130  /*
2131  * This is just m_normal[index] = n.Normalized(), but due to tiny floating point errors, causes
2132  * different outputs, so I'm leaving it
2133  */
2134  HullPlane n(p0, p1, p2);
2135  n = n.Scale(double(1.0) / n.GetNorm());
2136  n.GetW() = double(0.0);
2137  int index = dBitReversal(count, int(m_normal.size()));
2138  m_normal[index] = n;
2139  count++;
2140  assert(count <= int(m_normal.size()));
2141  }
2142 }
2143 
2144 ConvexHull::ndNormalMap::ndNormalMap()
2145 {
2146  VHACD::Vect3 p0(double(1.0), double(0.0), double(0.0));
2147  VHACD::Vect3 p1(double(-1.0), double(0.0), double(0.0));
2148  VHACD::Vect3 p2(double(0.0), double(1.0), double(0.0));
2149  VHACD::Vect3 p3(double(0.0), double(-1.0), double(0.0));
2150  VHACD::Vect3 p4(double(0.0), double(0.0), double(1.0));
2151  VHACD::Vect3 p5(double(0.0), double(0.0), double(-1.0));
2152 
2153  int count = 0;
2154  int subdivisions = 2;
2155  TessellateTriangle(subdivisions, p4, p0, p2, count);
2156  TessellateTriangle(subdivisions, p0, p5, p2, count);
2157  TessellateTriangle(subdivisions, p5, p1, p2, count);
2158  TessellateTriangle(subdivisions, p1, p4, p2, count);
2159  TessellateTriangle(subdivisions, p0, p4, p3, count);
2160  TessellateTriangle(subdivisions, p5, p0, p3, count);
2161  TessellateTriangle(subdivisions, p1, p5, p3, count);
2162  TessellateTriangle(subdivisions, p4, p1, p3, count);
2163 }
2164 
2165 ConvexHull::ConvexHull(const std::vector<::VHACD::Vertex>& vertexCloud, double distTol, int maxVertexCount)
2166 {
2167  if (vertexCloud.size() >= 4)
2168  {
2169  BuildHull(vertexCloud, distTol, maxVertexCount);
2170  }
2171 }
2172 
2173 const std::vector<VHACD::Vect3>& ConvexHull::GetVertexPool() const { return m_points; }
2174 
2175 void ConvexHull::BuildHull(const std::vector<::VHACD::Vertex>& vertexCloud, double distTol, int maxVertexCount)
2176 {
2177  size_t treeCount = vertexCloud.size() / (VHACD_CONVEXHULL_3D_VERTEX_CLUSTER_SIZE >> 1);
2178  treeCount = std::max(treeCount, size_t(4)) * 2;
2179 
2180  std::vector<ConvexHullVertex> points(vertexCloud.size());
2181  /*
2182  * treePool provides a memory pool for the AABB tree
2183  * Each node is either a leaf or non-leaf node
2184  * Non-leaf nodes have up to 8 vertices
2185  * Vertices are specified by the m_indices array and are accessed via the points array
2186  *
2187  * Later on in ConvexHull::SupportVertex, the tree is used directly
2188  * It differentiates between ConvexHullAABBTreeNode and ConvexHull3DPointCluster by whether the m_left and m_right
2189  * pointers are null or not
2190  *
2191  * Pointers have to be stable
2192  */
2193  NodeBundle<ConvexHullAABBTreeNode> treePool;
2194  for (size_t i = 0; i < vertexCloud.size(); ++i)
2195  {
2196  points[i] = VHACD::Vect3(vertexCloud[i]);
2197  }
2198  int count = InitVertexArray(points, treePool);
2199 
2200  if (m_points.size() >= 4)
2201  {
2202  CalculateConvexHull3D(&treePool.GetFirstNode(), points, count, distTol, maxVertexCount);
2203  }
2204 }
2205 
2206 void ConvexHull::GetUniquePoints(std::vector<ConvexHullVertex>& points)
2207 {
2208  class CompareVertex
2209  {
2210  public:
2211  int Compare(const ConvexHullVertex& elementA, const ConvexHullVertex& elementB) const
2212  {
2213  for (int i = 0; i < 3; i++)
2214  {
2215  if (elementA[i] < elementB[i])
2216  {
2217  return -1;
2218  }
2219  else if (elementA[i] > elementB[i])
2220  {
2221  return 1;
2222  }
2223  }
2224  return 0;
2225  }
2226  };
2227 
2228  int count = int(points.size());
2229  Sort<ConvexHullVertex, CompareVertex>(points.data(), count);
2230 
2231  int indexCount = 0;
2232  CompareVertex compareVertex;
2233  for (int i = 1; i < count; ++i)
2234  {
2235  for (; i < count; ++i)
2236  {
2237  if (compareVertex.Compare(points[indexCount], points[i]))
2238  {
2239  indexCount++;
2240  points[indexCount] = points[i];
2241  break;
2242  }
2243  }
2244  }
2245  points.resize(indexCount + 1);
2246 }
2247 
2248 ConvexHullAABBTreeNode* ConvexHull::BuildTreeRecurse(ConvexHullAABBTreeNode* const parent,
2249  ConvexHullVertex* const points,
2250  int count,
2251  int baseIndex,
2252  NodeBundle<ConvexHullAABBTreeNode>& memoryPool) const
2253 {
2254  ConvexHullAABBTreeNode* tree = nullptr;
2255 
2256  assert(count);
2257  VHACD::Vect3 minP(double(1.0e15));
2258  VHACD::Vect3 maxP(-double(1.0e15));
2259  if (count <= VHACD_CONVEXHULL_3D_VERTEX_CLUSTER_SIZE)
2260  {
2261  ConvexHullAABBTreeNode& clump = memoryPool.GetNextNode();
2262 
2263  clump.m_count = count;
2264  for (int i = 0; i < count; ++i)
2265  {
2266  clump.m_indices[i] = i + baseIndex;
2267 
2268  const VHACD::Vect3& p = points[i];
2269  minP = minP.CWiseMin(p);
2270  maxP = maxP.CWiseMax(p);
2271  }
2272 
2273  clump.m_left = nullptr;
2274  clump.m_right = nullptr;
2275  tree = &clump;
2276  }
2277  else
2278  {
2279  VHACD::Vect3 median(0);
2280  VHACD::Vect3 varian(0);
2281  for (int i = 0; i < count; ++i)
2282  {
2283  const VHACD::Vect3& p = points[i];
2284  minP = minP.CWiseMin(p);
2285  maxP = maxP.CWiseMax(p);
2286  median += p;
2287  varian += p.CWiseMul(p);
2288  }
2289 
2290  varian = varian * double(count) - median.CWiseMul(median);
2291  int index = 0;
2292  double maxVarian = double(-1.0e10);
2293  for (int i = 0; i < 3; ++i)
2294  {
2295  if (varian[i] > maxVarian)
2296  {
2297  index = i;
2298  maxVarian = varian[i];
2299  }
2300  }
2301  VHACD::Vect3 center(median * (double(1.0) / double(count)));
2302 
2303  double test = center[index];
2304 
2305  int i0 = 0;
2306  int i1 = count - 1;
2307  do
2308  {
2309  for (; i0 <= i1; i0++)
2310  {
2311  double val = points[i0][index];
2312  if (val > test)
2313  {
2314  break;
2315  }
2316  }
2317 
2318  for (; i1 >= i0; i1--)
2319  {
2320  double val = points[i1][index];
2321  if (val < test)
2322  {
2323  break;
2324  }
2325  }
2326 
2327  if (i0 < i1)
2328  {
2329  std::swap(points[i0], points[i1]);
2330  i0++;
2331  i1--;
2332  }
2333  } while (i0 <= i1);
2334 
2335  if (i0 == 0)
2336  {
2337  i0 = count / 2;
2338  }
2339  if (i0 >= (count - 1))
2340  {
2341  i0 = count / 2;
2342  }
2343 
2344  tree = &memoryPool.GetNextNode();
2345 
2346  assert(i0);
2347  assert(count - i0);
2348 
2349  tree->m_left = BuildTreeRecurse(tree, points, i0, baseIndex, memoryPool);
2350  tree->m_right = BuildTreeRecurse(tree, &points[i0], count - i0, i0 + baseIndex, memoryPool);
2351  }
2352 
2353  assert(tree);
2354  tree->m_parent = parent;
2355  /*
2356  * WARNING: Changing the compiler conversion of 1.0e-3f changes the results of the convex decomposition
2357  * Inflate the tree's bounding box slightly
2358  */
2359  tree->m_box[0] = minP - VHACD::Vect3(double(1.0e-3f));
2360  tree->m_box[1] = maxP + VHACD::Vect3(double(1.0e-3f));
2361  return tree;
2362 }
2363 
2364 ConvexHullAABBTreeNode* ConvexHull::BuildTreeOld(std::vector<ConvexHullVertex>& points,
2365  NodeBundle<ConvexHullAABBTreeNode>& memoryPool)
2366 {
2367  GetUniquePoints(points);
2368  int count = int(points.size());
2369  if (count < 4)
2370  {
2371  return nullptr;
2372  }
2373  return BuildTreeRecurse(nullptr, points.data(), count, 0, memoryPool);
2374 }
2375 
2376 ConvexHullAABBTreeNode* ConvexHull::BuildTreeNew(std::vector<ConvexHullVertex>& points,
2377  std::vector<ConvexHullAABBTreeNode>& memoryPool) const
2378 {
2379  class dCluster
2380  {
2381  public:
2382  VHACD::Vect3 m_sum{ double(0.0) };
2383  VHACD::Vect3 m_sum2{ double(0.0) };
2384  int m_start{ 0 };
2385  int m_count{ 0 };
2386  };
2387 
2388  dCluster firstCluster;
2389  firstCluster.m_count = int(points.size());
2390 
2391  for (int i = 0; i < firstCluster.m_count; ++i)
2392  {
2393  const VHACD::Vect3& p = points[i];
2394  firstCluster.m_sum += p;
2395  firstCluster.m_sum2 += p.CWiseMul(p);
2396  }
2397 
2398  int baseCount = 0;
2399  const int clusterSize = 16;
2400 
2401  if (firstCluster.m_count > clusterSize)
2402  {
2403  dCluster spliteStack[128];
2404  spliteStack[0] = firstCluster;
2405  size_t stack = 1;
2406 
2407  while (stack)
2408  {
2409  stack--;
2410  dCluster cluster(spliteStack[stack]);
2411 
2412  const VHACD::Vect3 origin(cluster.m_sum * (double(1.0) / cluster.m_count));
2413  const VHACD::Vect3 variance2(cluster.m_sum2 * (double(1.0) / cluster.m_count) - origin.CWiseMul(origin));
2414  double maxVariance2 = variance2.MaxCoeff();
2415 
2416  if ((cluster.m_count <= clusterSize) || (stack > (sizeof(spliteStack) / sizeof(spliteStack[0]) - 4)) ||
2417  (maxVariance2 < 1.e-4f))
2418  {
2419  // no sure if this is beneficial,
2420  // the array is so small that seem too much overhead
2421  // int maxIndex = 0;
2422  // double min_x = 1.0e20f;
2423  // for (int i = 0; i < cluster.m_count; ++i)
2424  //{
2425  // if (points[cluster.m_start + i].getX() < min_x)
2426  // {
2427  // maxIndex = i;
2428  // min_x = points[cluster.m_start + i].getX();
2429  // }
2430  //}
2431  // Swap(points[cluster.m_start], points[cluster.m_start + maxIndex]);
2432  //
2433  // for (int i = 2; i < cluster.m_count; ++i)
2434  //{
2435  // int j = i;
2436  // ConvexHullVertex tmp(points[cluster.m_start + i]);
2437  // for (; points[cluster.m_start + j - 1].getX() > tmp.getX(); --j)
2438  // {
2439  // assert(j > 0);
2440  // points[cluster.m_start + j] = points[cluster.m_start + j - 1];
2441  // }
2442  // points[cluster.m_start + j] = tmp;
2443  //}
2444 
2445  int count = cluster.m_count;
2446  for (int i = cluster.m_count - 1; i > 0; --i)
2447  {
2448  for (int j = i - 1; j >= 0; --j)
2449  {
2450  VHACD::Vect3 error(points[cluster.m_start + j] - points[cluster.m_start + i]);
2451  double mag2 = error.Dot(error);
2452  if (mag2 < double(1.0e-6))
2453  {
2454  points[cluster.m_start + j] = points[cluster.m_start + i];
2455  count--;
2456  break;
2457  }
2458  }
2459  }
2460 
2461  assert(baseCount <= cluster.m_start);
2462  for (int i = 0; i < count; ++i)
2463  {
2464  points[baseCount] = points[cluster.m_start + i];
2465  baseCount++;
2466  }
2467  }
2468  else
2469  {
2470  const int firstSortAxis = variance2.LongestAxis();
2471  double axisVal = origin[firstSortAxis];
2472 
2473  int i0 = 0;
2474  int i1 = cluster.m_count - 1;
2475 
2476  const int start = cluster.m_start;
2477  while (i0 < i1)
2478  {
2479  while ((points[start + i0][firstSortAxis] <= axisVal) && (i0 < i1))
2480  {
2481  ++i0;
2482  };
2483 
2484  while ((points[start + i1][firstSortAxis] > axisVal) && (i0 < i1))
2485  {
2486  --i1;
2487  }
2488 
2489  assert(i0 <= i1);
2490  if (i0 < i1)
2491  {
2492  std::swap(points[start + i0], points[start + i1]);
2493  ++i0;
2494  --i1;
2495  }
2496  }
2497 
2498  while ((points[start + i0][firstSortAxis] <= axisVal) && (i0 < cluster.m_count))
2499  {
2500  ++i0;
2501  };
2502 
2503 #ifdef _DEBUG
2504  for (int i = 0; i < i0; ++i)
2505  {
2506  assert(points[start + i][firstSortAxis] <= axisVal);
2507  }
2508 
2509  for (int i = i0; i < cluster.m_count; ++i)
2510  {
2511  assert(points[start + i][firstSortAxis] > axisVal);
2512  }
2513 #endif
2514 
2515  VHACD::Vect3 xc(0);
2516  VHACD::Vect3 x2c(0);
2517  for (int i = 0; i < i0; ++i)
2518  {
2519  const VHACD::Vect3& x = points[start + i];
2520  xc += x;
2521  x2c += x.CWiseMul(x);
2522  }
2523 
2524  dCluster cluster_i1(cluster);
2525  cluster_i1.m_start = start + i0;
2526  cluster_i1.m_count = cluster.m_count - i0;
2527  cluster_i1.m_sum -= xc;
2528  cluster_i1.m_sum2 -= x2c;
2529  spliteStack[stack] = cluster_i1;
2530  assert(cluster_i1.m_count > 0);
2531  stack++;
2532 
2533  dCluster cluster_i0(cluster);
2534  cluster_i0.m_start = start;
2535  cluster_i0.m_count = i0;
2536  cluster_i0.m_sum = xc;
2537  cluster_i0.m_sum2 = x2c;
2538  assert(cluster_i0.m_count > 0);
2539  spliteStack[stack] = cluster_i0;
2540  stack++;
2541  }
2542  }
2543  }
2544 
2545  points.resize(baseCount);
2546  if (baseCount < 4)
2547  {
2548  return nullptr;
2549  }
2550 
2551  VHACD::Vect3 sum(0);
2552  VHACD::Vect3 sum2(0);
2553  VHACD::Vect3 minP(double(1.0e15));
2554  VHACD::Vect3 maxP(double(-1.0e15));
2555  class dTreeBox
2556  {
2557  public:
2558  VHACD::Vect3 m_min;
2559  VHACD::Vect3 m_max;
2560  VHACD::Vect3 m_sum;
2561  VHACD::Vect3 m_sum2;
2562  ConvexHullAABBTreeNode* m_parent;
2563  ConvexHullAABBTreeNode** m_child;
2564  int m_start;
2565  int m_count;
2566  };
2567 
2568  for (int i = 0; i < baseCount; ++i)
2569  {
2570  const VHACD::Vect3& p = points[i];
2571  sum += p;
2572  sum2 += p.CWiseMul(p);
2573  minP = minP.CWiseMin(p);
2574  maxP = maxP.CWiseMax(p);
2575  }
2576 
2577  dTreeBox treeBoxStack[128];
2578  treeBoxStack[0].m_start = 0;
2579  treeBoxStack[0].m_count = baseCount;
2580  treeBoxStack[0].m_sum = sum;
2581  treeBoxStack[0].m_sum2 = sum2;
2582  treeBoxStack[0].m_min = minP;
2583  treeBoxStack[0].m_max = maxP;
2584  treeBoxStack[0].m_child = nullptr;
2585  treeBoxStack[0].m_parent = nullptr;
2586 
2587  int stack = 1;
2588  ConvexHullAABBTreeNode* root = nullptr;
2589  while (stack)
2590  {
2591  stack--;
2592  dTreeBox box(treeBoxStack[stack]);
2593  if (box.m_count <= VHACD_CONVEXHULL_3D_VERTEX_CLUSTER_SIZE)
2594  {
2595  assert(memoryPool.size() != memoryPool.capacity() && "memoryPool is going to be reallocated, pointers will be "
2596  "invalid");
2597  memoryPool.emplace_back();
2598  ConvexHullAABBTreeNode& clump = memoryPool.back();
2599 
2600  clump.m_count = box.m_count;
2601  for (int i = 0; i < box.m_count; ++i)
2602  {
2603  clump.m_indices[i] = i + box.m_start;
2604  }
2605  clump.m_box[0] = box.m_min;
2606  clump.m_box[1] = box.m_max;
2607 
2608  if (box.m_child)
2609  {
2610  *box.m_child = &clump;
2611  }
2612 
2613  if (!root)
2614  {
2615  root = &clump;
2616  }
2617  }
2618  else
2619  {
2620  const VHACD::Vect3 origin(box.m_sum * (double(1.0) / box.m_count));
2621  const VHACD::Vect3 variance2(box.m_sum2 * (double(1.0) / box.m_count) - origin.CWiseMul(origin));
2622 
2623  int firstSortAxis = 0;
2624  if ((variance2.GetY() >= variance2.GetX()) && (variance2.GetY() >= variance2.GetZ()))
2625  {
2626  firstSortAxis = 1;
2627  }
2628  else if ((variance2.GetZ() >= variance2.GetX()) && (variance2.GetZ() >= variance2.GetY()))
2629  {
2630  firstSortAxis = 2;
2631  }
2632  double axisVal = origin[firstSortAxis];
2633 
2634  int i0 = 0;
2635  int i1 = box.m_count - 1;
2636 
2637  const int start = box.m_start;
2638  while (i0 < i1)
2639  {
2640  while ((points[start + i0][firstSortAxis] <= axisVal) && (i0 < i1))
2641  {
2642  ++i0;
2643  };
2644 
2645  while ((points[start + i1][firstSortAxis] > axisVal) && (i0 < i1))
2646  {
2647  --i1;
2648  }
2649 
2650  assert(i0 <= i1);
2651  if (i0 < i1)
2652  {
2653  std::swap(points[start + i0], points[start + i1]);
2654  ++i0;
2655  --i1;
2656  }
2657  }
2658 
2659  while ((points[start + i0][firstSortAxis] <= axisVal) && (i0 < box.m_count))
2660  {
2661  ++i0;
2662  };
2663 
2664 #ifdef _DEBUG
2665  for (int i = 0; i < i0; ++i)
2666  {
2667  assert(points[start + i][firstSortAxis] <= axisVal);
2668  }
2669 
2670  for (int i = i0; i < box.m_count; ++i)
2671  {
2672  assert(points[start + i][firstSortAxis] > axisVal);
2673  }
2674 #endif
2675 
2676  assert(memoryPool.size() != memoryPool.capacity() && "memoryPool is going to be reallocated, pointers will be "
2677  "invalid");
2678  memoryPool.emplace_back();
2679  ConvexHullAABBTreeNode& node = memoryPool.back();
2680 
2681  node.m_box[0] = box.m_min;
2682  node.m_box[1] = box.m_max;
2683  if (box.m_child)
2684  {
2685  *box.m_child = &node;
2686  }
2687 
2688  if (!root)
2689  {
2690  root = &node;
2691  }
2692 
2693  {
2694  VHACD::Vect3 xc(0);
2695  VHACD::Vect3 x2c(0);
2696  VHACD::Vect3 p0(double(1.0e15));
2697  VHACD::Vect3 p1(double(-1.0e15));
2698  for (int i = i0; i < box.m_count; ++i)
2699  {
2700  const VHACD::Vect3& p = points[start + i];
2701  xc += p;
2702  x2c += p.CWiseMul(p);
2703  p0 = p0.CWiseMin(p);
2704  p1 = p1.CWiseMax(p);
2705  }
2706 
2707  dTreeBox cluster_i1(box);
2708  cluster_i1.m_start = start + i0;
2709  cluster_i1.m_count = box.m_count - i0;
2710  cluster_i1.m_sum = xc;
2711  cluster_i1.m_sum2 = x2c;
2712  cluster_i1.m_min = p0;
2713  cluster_i1.m_max = p1;
2714  cluster_i1.m_parent = &node;
2715  cluster_i1.m_child = &node.m_right;
2716  treeBoxStack[stack] = cluster_i1;
2717  assert(cluster_i1.m_count > 0);
2718  stack++;
2719  }
2720 
2721  {
2722  VHACD::Vect3 xc(0);
2723  VHACD::Vect3 x2c(0);
2724  VHACD::Vect3 p0(double(1.0e15));
2725  VHACD::Vect3 p1(double(-1.0e15));
2726  for (int i = 0; i < i0; ++i)
2727  {
2728  const VHACD::Vect3& p = points[start + i];
2729  xc += p;
2730  x2c += p.CWiseMul(p);
2731  p0 = p0.CWiseMin(p);
2732  p1 = p1.CWiseMax(p);
2733  }
2734 
2735  dTreeBox cluster_i0(box);
2736  cluster_i0.m_start = start;
2737  cluster_i0.m_count = i0;
2738  cluster_i0.m_min = p0;
2739  cluster_i0.m_max = p1;
2740  cluster_i0.m_sum = xc;
2741  cluster_i0.m_sum2 = x2c;
2742  cluster_i0.m_parent = &node;
2743  cluster_i0.m_child = &node.m_left;
2744  assert(cluster_i0.m_count > 0);
2745  treeBoxStack[stack] = cluster_i0;
2746  stack++;
2747  }
2748  }
2749  }
2750 
2751  return root;
2752 }
2753 
2754 int ConvexHull::SupportVertex(ConvexHullAABBTreeNode** const treePointer,
2755  const std::vector<ConvexHullVertex>& points,
2756  const VHACD::Vect3& dirPlane,
2757  const bool removeEntry) const
2758 {
2759 #define VHACD_STACK_DEPTH_3D 64
2760  double aabbProjection[VHACD_STACK_DEPTH_3D];
2761  ConvexHullAABBTreeNode* stackPool[VHACD_STACK_DEPTH_3D];
2762 
2763  VHACD::Vect3 dir(dirPlane);
2764 
2765  int index = -1;
2766  int stack = 1;
2767  stackPool[0] = *treePointer;
2768  aabbProjection[0] = double(1.0e20);
2769  double maxProj = double(-1.0e20);
2770  int ix = (dir[0] > double(0.0)) ? 1 : 0;
2771  int iy = (dir[1] > double(0.0)) ? 1 : 0;
2772  int iz = (dir[2] > double(0.0)) ? 1 : 0;
2773  while (stack)
2774  {
2775  stack--;
2776  double boxSupportValue = aabbProjection[stack];
2777  if (boxSupportValue > maxProj)
2778  {
2779  ConvexHullAABBTreeNode* me = stackPool[stack];
2780 
2781  /*
2782  * If the node is not a leaf node...
2783  */
2784  if (me->m_left && me->m_right)
2785  {
2786  const VHACD::Vect3 leftSupportPoint(
2787  me->m_left->m_box[ix].GetX(), me->m_left->m_box[iy].GetY(), me->m_left->m_box[iz].GetZ());
2788  double leftSupportDist = leftSupportPoint.Dot(dir);
2789 
2790  const VHACD::Vect3 rightSupportPoint(
2791  me->m_right->m_box[ix].GetX(), me->m_right->m_box[iy].GetY(), me->m_right->m_box[iz].GetZ());
2792  double rightSupportDist = rightSupportPoint.Dot(dir);
2793 
2794  /*
2795  * ...push the shorter side first
2796  * So we can explore the tree in the larger side first
2797  */
2798  if (rightSupportDist >= leftSupportDist)
2799  {
2800  aabbProjection[stack] = leftSupportDist;
2801  stackPool[stack] = me->m_left;
2802  stack++;
2803  assert(stack < VHACD_STACK_DEPTH_3D);
2804  aabbProjection[stack] = rightSupportDist;
2805  stackPool[stack] = me->m_right;
2806  stack++;
2807  assert(stack < VHACD_STACK_DEPTH_3D);
2808  }
2809  else
2810  {
2811  aabbProjection[stack] = rightSupportDist;
2812  stackPool[stack] = me->m_right;
2813  stack++;
2814  assert(stack < VHACD_STACK_DEPTH_3D);
2815  aabbProjection[stack] = leftSupportDist;
2816  stackPool[stack] = me->m_left;
2817  stack++;
2818  assert(stack < VHACD_STACK_DEPTH_3D);
2819  }
2820  }
2821  /*
2822  * If it is a node...
2823  */
2824  else
2825  {
2826  ConvexHullAABBTreeNode* cluster = me;
2827  for (size_t i = 0; i < cluster->m_count; ++i)
2828  {
2829  const ConvexHullVertex& p = points[cluster->m_indices[i]];
2830  assert(p.GetX() >= cluster->m_box[0].GetX());
2831  assert(p.GetX() <= cluster->m_box[1].GetX());
2832  assert(p.GetY() >= cluster->m_box[0].GetY());
2833  assert(p.GetY() <= cluster->m_box[1].GetY());
2834  assert(p.GetZ() >= cluster->m_box[0].GetZ());
2835  assert(p.GetZ() <= cluster->m_box[1].GetZ());
2836  if (!p.m_mark)
2837  {
2838  // assert(p.m_w == double(0.0f));
2839  double dist = p.Dot(dir);
2840  if (dist > maxProj)
2841  {
2842  maxProj = dist;
2843  index = cluster->m_indices[i];
2844  }
2845  }
2846  else if (removeEntry)
2847  {
2848  cluster->m_indices[i] = cluster->m_indices[cluster->m_count - 1];
2849  cluster->m_count = cluster->m_count - 1;
2850  i--;
2851  }
2852  }
2853 
2854  if (cluster->m_count == 0)
2855  {
2856  ConvexHullAABBTreeNode* const parent = cluster->m_parent;
2857  if (parent)
2858  {
2859  ConvexHullAABBTreeNode* const sibling = (parent->m_left != cluster) ? parent->m_left : parent->m_right;
2860  assert(sibling != cluster);
2861  ConvexHullAABBTreeNode* const grandParent = parent->m_parent;
2862  if (grandParent)
2863  {
2864  sibling->m_parent = grandParent;
2865  if (grandParent->m_right == parent)
2866  {
2867  grandParent->m_right = sibling;
2868  }
2869  else
2870  {
2871  grandParent->m_left = sibling;
2872  }
2873  }
2874  else
2875  {
2876  sibling->m_parent = nullptr;
2877  *treePointer = sibling;
2878  }
2879  }
2880  }
2881  }
2882  }
2883  }
2884 
2885  assert(index != -1);
2886  return index;
2887 }
2888 
2889 double ConvexHull::TetrahedrumVolume(const VHACD::Vect3& p0,
2890  const VHACD::Vect3& p1,
2891  const VHACD::Vect3& p2,
2892  const VHACD::Vect3& p3) const
2893 {
2894  const VHACD::Vect3 p1p0(p1 - p0);
2895  const VHACD::Vect3 p2p0(p2 - p0);
2896  const VHACD::Vect3 p3p0(p3 - p0);
2897  return p3p0.Dot(p1p0.Cross(p2p0));
2898 }
2899 
2900 int ConvexHull::InitVertexArray(std::vector<ConvexHullVertex>& points, NodeBundle<ConvexHullAABBTreeNode>& memoryPool)
2901 // std::vector<ConvexHullAABBTreeNode>& memoryPool)
2902 {
2903 #if 1
2904  ConvexHullAABBTreeNode* tree = BuildTreeOld(points, memoryPool);
2905 #else
2906  ConvexHullAABBTreeNode* tree = BuildTreeNew(points, (char**)&memoryPool, maxMemSize);
2907 #endif
2908  int count = int(points.size());
2909  if (count < 4)
2910  {
2911  m_points.resize(0);
2912  return 0;
2913  }
2914 
2915  m_points.resize(count);
2916  m_aabbP0 = tree->m_box[0];
2917  m_aabbP1 = tree->m_box[1];
2918 
2919  VHACD::Vect3 boxSize(tree->m_box[1] - tree->m_box[0]);
2920  m_diag = boxSize.GetNorm();
2921  const ndNormalMap& normalMap = ndNormalMap::GetNormalMap();
2922 
2923  int index0 = SupportVertex(&tree, points, normalMap.m_normal[0]);
2924  m_points[0] = points[index0];
2925  points[index0].m_mark = 1;
2926 
2927  bool validTetrahedrum = false;
2928  VHACD::Vect3 e1(double(0.0));
2929  for (int i = 1; i < normalMap.m_count; ++i)
2930  {
2931  int index = SupportVertex(&tree, points, normalMap.m_normal[i]);
2932  assert(index >= 0);
2933 
2934  e1 = points[index] - m_points[0];
2935  double error2 = e1.GetNormSquared();
2936  if (error2 > (double(1.0e-4) * m_diag * m_diag))
2937  {
2938  m_points[1] = points[index];
2939  points[index].m_mark = 1;
2940  validTetrahedrum = true;
2941  break;
2942  }
2943  }
2944  if (!validTetrahedrum)
2945  {
2946  m_points.resize(0);
2947  assert(0);
2948  return count;
2949  }
2950 
2951  validTetrahedrum = false;
2952  VHACD::Vect3 e2(double(0.0));
2953  VHACD::Vect3 normal(double(0.0));
2954  for (int i = 2; i < normalMap.m_count; ++i)
2955  {
2956  int index = SupportVertex(&tree, points, normalMap.m_normal[i]);
2957  assert(index >= 0);
2958  e2 = points[index] - m_points[0];
2959  normal = e1.Cross(e2);
2960  double error2 = normal.GetNorm();
2961  if (error2 > (double(1.0e-4) * m_diag * m_diag))
2962  {
2963  m_points[2] = points[index];
2964  points[index].m_mark = 1;
2965  validTetrahedrum = true;
2966  break;
2967  }
2968  }
2969 
2970  if (!validTetrahedrum)
2971  {
2972  m_points.resize(0);
2973  assert(0);
2974  return count;
2975  }
2976 
2977  // find the largest possible tetrahedron
2978  validTetrahedrum = false;
2979  VHACD::Vect3 e3(double(0.0));
2980 
2981  index0 = SupportVertex(&tree, points, normal);
2982  e3 = points[index0] - m_points[0];
2983  double err2 = normal.Dot(e3);
2984  if (fabs(err2) > (double(1.0e-6) * m_diag * m_diag))
2985  {
2986  // we found a valid tetrahedral, about and start build the hull by adding the rest of the points
2987  m_points[3] = points[index0];
2988  points[index0].m_mark = 1;
2989  validTetrahedrum = true;
2990  }
2991  if (!validTetrahedrum)
2992  {
2993  VHACD::Vect3 n(-normal);
2994  int index = SupportVertex(&tree, points, n);
2995  e3 = points[index] - m_points[0];
2996  double error2 = normal.Dot(e3);
2997  if (fabs(error2) > (double(1.0e-6) * m_diag * m_diag))
2998  {
2999  // we found a valid tetrahedral, about and start build the hull by adding the rest of the points
3000  m_points[3] = points[index];
3001  points[index].m_mark = 1;
3002  validTetrahedrum = true;
3003  }
3004  }
3005  if (!validTetrahedrum)
3006  {
3007  for (int i = 3; i < normalMap.m_count; ++i)
3008  {
3009  int index = SupportVertex(&tree, points, normalMap.m_normal[i]);
3010  assert(index >= 0);
3011 
3012  // make sure the volume of the fist tetrahedral is no negative
3013  e3 = points[index] - m_points[0];
3014  double error2 = normal.Dot(e3);
3015  if (fabs(error2) > (double(1.0e-6) * m_diag * m_diag))
3016  {
3017  // we found a valid tetrahedral, about and start build the hull by adding the rest of the points
3018  m_points[3] = points[index];
3019  points[index].m_mark = 1;
3020  validTetrahedrum = true;
3021  break;
3022  }
3023  }
3024  }
3025  if (!validTetrahedrum)
3026  {
3027  // the points do not form a convex hull
3028  m_points.resize(0);
3029  return count;
3030  }
3031 
3032  m_points.resize(4);
3033  double volume = TetrahedrumVolume(m_points[0], m_points[1], m_points[2], m_points[3]);
3034  if (volume > double(0.0))
3035  {
3036  std::swap(m_points[2], m_points[3]);
3037  }
3038  assert(TetrahedrumVolume(m_points[0], m_points[1], m_points[2], m_points[3]) < double(0.0));
3039  return count;
3040 }
3041 
3042 std::list<ConvexHullFace>::iterator ConvexHull::AddFace(int i0, int i1, int i2)
3043 {
3044  ConvexHullFace face;
3045  face.m_index[0] = i0;
3046  face.m_index[1] = i1;
3047  face.m_index[2] = i2;
3048 
3049  std::list<ConvexHullFace>::iterator node = m_list.emplace(m_list.end(), face);
3050  return node;
3051 }
3052 
3053 void ConvexHull::CalculateConvexHull3D(ConvexHullAABBTreeNode* vertexTree,
3054  std::vector<ConvexHullVertex>& points,
3055  int count,
3056  double distTol,
3057  int maxVertexCount)
3058 {
3059  distTol = fabs(distTol) * m_diag;
3060  std::list<ConvexHullFace>::iterator f0Node = AddFace(0, 1, 2);
3061  std::list<ConvexHullFace>::iterator f1Node = AddFace(0, 2, 3);
3062  std::list<ConvexHullFace>::iterator f2Node = AddFace(2, 1, 3);
3063  std::list<ConvexHullFace>::iterator f3Node = AddFace(1, 0, 3);
3064 
3065  ConvexHullFace& f0 = *f0Node;
3066  ConvexHullFace& f1 = *f1Node;
3067  ConvexHullFace& f2 = *f2Node;
3068  ConvexHullFace& f3 = *f3Node;
3069 
3070  f0.m_twin[0] = f3Node;
3071  f0.m_twin[1] = f2Node;
3072  f0.m_twin[2] = f1Node;
3073 
3074  f1.m_twin[0] = f0Node;
3075  f1.m_twin[1] = f2Node;
3076  f1.m_twin[2] = f3Node;
3077 
3078  f2.m_twin[0] = f0Node;
3079  f2.m_twin[1] = f3Node;
3080  f2.m_twin[2] = f1Node;
3081 
3082  f3.m_twin[0] = f0Node;
3083  f3.m_twin[1] = f1Node;
3084  f3.m_twin[2] = f2Node;
3085 
3086  std::list<std::list<ConvexHullFace>::iterator> boundaryFaces;
3087  boundaryFaces.push_back(f0Node);
3088  boundaryFaces.push_back(f1Node);
3089  boundaryFaces.push_back(f2Node);
3090  boundaryFaces.push_back(f3Node);
3091 
3092  m_points.resize(count);
3093 
3094  count -= 4;
3095  maxVertexCount -= 4;
3096  int currentIndex = 4;
3097 
3098  /*
3099  * Some are iterators into boundaryFaces, others into m_list
3100  */
3101  std::vector<std::list<ConvexHullFace>::iterator> stack;
3102  std::vector<std::list<ConvexHullFace>::iterator> coneList;
3103  std::vector<std::list<ConvexHullFace>::iterator> deleteList;
3104 
3105  stack.reserve(1024 + count);
3106  coneList.reserve(1024 + count);
3107  deleteList.reserve(1024 + count);
3108 
3109  while (boundaryFaces.size() && count && (maxVertexCount > 0))
3110  {
3111  // my definition of the optimal convex hull of a given vertex count,
3112  // is the convex hull formed by a subset of the input vertex that minimizes the volume difference
3113  // between the perfect hull formed from all input vertex and the hull of the sub set of vertex.
3114  // When using a priority heap this algorithms will generate the an optimal of a fix vertex count.
3115  // Since all Newton's tools do not have a limit on the point count of a convex hull, I can use either a stack or a
3116  // queue. a stack maximize construction speed, a Queue tend to maximize the volume of the generated Hull approaching
3117  // a perfect Hull. For now we use a queue. For general hulls it does not make a difference if we use a stack, queue,
3118  // or a priority heap. perfect optimal hull only apply for when build hull of a limited vertex count.
3119  //
3120  // Also when building Hulls of a limited vertex count, this function runs in constant time.
3121  // yes that is correct, it does not makes a difference if you build a N point hull from 100 vertex
3122  // or from 100000 vertex input array.
3123 
3124  // using a queue (some what slower by better hull when reduced vertex count is desired)
3125  bool isvalid;
3126  std::list<ConvexHullFace>::iterator faceNode = boundaryFaces.back();
3127  ConvexHullFace& face = *faceNode;
3128  HullPlane planeEquation(face.GetPlaneEquation(m_points, isvalid));
3129 
3130  int index = 0;
3131  double dist = 0;
3132  VHACD::Vect3 p;
3133  if (isvalid)
3134  {
3135  index = SupportVertex(&vertexTree, points, planeEquation);
3136  p = points[index];
3137  dist = planeEquation.Evalue(p);
3138  }
3139 
3140  if (isvalid && (dist >= distTol) && (face.Evalue(m_points, p) < double(0.0)))
3141  {
3142  stack.push_back(faceNode);
3143 
3144  deleteList.clear();
3145  while (stack.size())
3146  {
3147  std::list<ConvexHullFace>::iterator node1 = stack.back();
3148  ConvexHullFace& face1 = *node1;
3149 
3150  stack.pop_back();
3151 
3152  if (!face1.m_mark && (face1.Evalue(m_points, p) < double(0.0)))
3153  {
3154 #ifdef _DEBUG
3155  for (const auto node : deleteList)
3156  {
3157  assert(node != node1);
3158  }
3159 #endif
3160 
3161  deleteList.push_back(node1);
3162  face1.m_mark = 1;
3163  for (std::list<ConvexHullFace>::iterator& twinNode : face1.m_twin)
3164  {
3165  ConvexHullFace& twinFace = *twinNode;
3166  if (!twinFace.m_mark)
3167  {
3168  stack.push_back(twinNode);
3169  }
3170  }
3171  }
3172  }
3173 
3174  m_points[currentIndex] = points[index];
3175  points[index].m_mark = 1;
3176 
3177  coneList.clear();
3178  for (std::list<ConvexHullFace>::iterator node1 : deleteList)
3179  {
3180  ConvexHullFace& face1 = *node1;
3181  assert(face1.m_mark == 1);
3182  for (std::size_t j0 = 0; j0 < face1.m_twin.size(); ++j0)
3183  {
3184  std::list<ConvexHullFace>::iterator twinNode = face1.m_twin[j0];
3185  ConvexHullFace& twinFace = *twinNode;
3186  if (!twinFace.m_mark)
3187  {
3188  std::size_t j1 = (j0 == 2) ? 0 : j0 + 1;
3189  std::list<ConvexHullFace>::iterator newNode = AddFace(currentIndex, face1.m_index[j0], face1.m_index[j1]);
3190  boundaryFaces.push_front(newNode);
3191  ConvexHullFace& newFace = *newNode;
3192 
3193  newFace.m_twin[1] = twinNode;
3194  for (std::size_t k = 0; k < twinFace.m_twin.size(); ++k)
3195  {
3196  if (twinFace.m_twin[k] == node1)
3197  {
3198  twinFace.m_twin[k] = newNode;
3199  }
3200  }
3201  coneList.push_back(newNode);
3202  }
3203  }
3204  }
3205 
3206  for (std::size_t i = 0; i < coneList.size() - 1; ++i)
3207  {
3208  std::list<ConvexHullFace>::iterator nodeA = coneList[i];
3209  ConvexHullFace& faceA = *nodeA;
3210  assert(faceA.m_mark == 0);
3211  for (std::size_t j = i + 1; j < coneList.size(); j++)
3212  {
3213  std::list<ConvexHullFace>::iterator nodeB = coneList[j];
3214  ConvexHullFace& faceB = *nodeB;
3215  assert(faceB.m_mark == 0);
3216  if (faceA.m_index[2] == faceB.m_index[1])
3217  {
3218  faceA.m_twin[2] = nodeB;
3219  faceB.m_twin[0] = nodeA;
3220  break;
3221  }
3222  }
3223 
3224  for (std::size_t j = i + 1; j < coneList.size(); j++)
3225  {
3226  std::list<ConvexHullFace>::iterator nodeB = coneList[j];
3227  ConvexHullFace& faceB = *nodeB;
3228  assert(faceB.m_mark == 0);
3229  if (faceA.m_index[1] == faceB.m_index[2])
3230  {
3231  faceA.m_twin[0] = nodeB;
3232  faceB.m_twin[2] = nodeA;
3233  break;
3234  }
3235  }
3236  }
3237 
3238  for (std::list<ConvexHullFace>::iterator node : deleteList)
3239  {
3240  auto it = std::find(boundaryFaces.begin(), boundaryFaces.end(), node);
3241  if (it != boundaryFaces.end())
3242  {
3243  boundaryFaces.erase(it);
3244  }
3245  m_list.erase(node);
3246  }
3247 
3248  maxVertexCount--;
3249  currentIndex++;
3250  count--;
3251  }
3252  else
3253  {
3254  auto it = std::find(boundaryFaces.begin(), boundaryFaces.end(), faceNode);
3255  if (it != boundaryFaces.end())
3256  {
3257  boundaryFaces.erase(it);
3258  }
3259  }
3260  }
3261  m_points.resize(currentIndex);
3262 }
3263 
3264 //***********************************************************************************************
3265 // End of ConvexHull generation code by Julio Jerez <jerezjulio0@gmail.com>
3266 //***********************************************************************************************
3267 
3268 class KdTreeNode;
3269 
3270 enum Axes
3271 {
3272  X_AXIS = 0,
3273  Y_AXIS = 1,
3274  Z_AXIS = 2
3275 };
3276 
3277 class KdTreeFindNode
3278 {
3279 public:
3280  KdTreeFindNode() = default;
3281 
3282  KdTreeNode* m_node{ nullptr };
3283  double m_distance{ 0.0 };
3284 };
3285 
3286 class KdTree
3287 {
3288 public:
3289  KdTree() = default;
3290 
3291  const VHACD::Vertex& GetPosition(uint32_t index) const;
3292 
3293  uint32_t Search(const VHACD::Vect3& pos, double radius, uint32_t maxObjects, KdTreeFindNode* found) const;
3294 
3295  uint32_t Add(const VHACD::Vertex& v);
3296 
3297  KdTreeNode& GetNewNode(uint32_t index);
3298 
3299  uint32_t GetNearest(const VHACD::Vect3& pos,
3300  double radius,
3301  bool& _found) const; // returns the nearest possible neighbor's index.
3302 
3303  const std::vector<VHACD::Vertex>& GetVertices() const;
3304  std::vector<VHACD::Vertex>&& TakeVertices();
3305 
3306  uint32_t GetVCount() const;
3307 
3308 private:
3309  KdTreeNode* m_root{ nullptr };
3310  NodeBundle<KdTreeNode> m_bundle;
3311 
3312  std::vector<VHACD::Vertex> m_vertices;
3313 };
3314 
3315 class KdTreeNode
3316 {
3317 public:
3318  KdTreeNode() = default;
3319  KdTreeNode(uint32_t index);
3320 
3321  void Add(KdTreeNode& node, Axes dim, const KdTree& iface);
3322 
3323  uint32_t GetIndex() const;
3324 
3325  void Search(Axes axis,
3326  const VHACD::Vect3& pos,
3327  double radius,
3328  uint32_t& count,
3329  uint32_t maxObjects,
3330  KdTreeFindNode* found,
3331  const KdTree& iface);
3332 
3333 private:
3334  uint32_t m_index = 0;
3335  KdTreeNode* m_left = nullptr;
3336  KdTreeNode* m_right = nullptr;
3337 };
3338 
3339 const VHACD::Vertex& KdTree::GetPosition(uint32_t index) const
3340 {
3341  assert(index < m_vertices.size());
3342  return m_vertices[index];
3343 }
3344 
3345 uint32_t KdTree::Search(const VHACD::Vect3& pos, double radius, uint32_t maxObjects, KdTreeFindNode* found) const
3346 {
3347  if (!m_root)
3348  return 0;
3349  uint32_t count = 0;
3350  m_root->Search(X_AXIS, pos, radius, count, maxObjects, found, *this);
3351  return count;
3352 }
3353 
3354 uint32_t KdTree::Add(const VHACD::Vertex& v)
3355 {
3356  uint32_t ret = uint32_t(m_vertices.size());
3357  m_vertices.emplace_back(v);
3358  KdTreeNode& node = GetNewNode(ret);
3359  if (m_root)
3360  {
3361  m_root->Add(node, X_AXIS, *this);
3362  }
3363  else
3364  {
3365  m_root = &node;
3366  }
3367  return ret;
3368 }
3369 
3370 KdTreeNode& KdTree::GetNewNode(uint32_t index)
3371 {
3372  KdTreeNode& node = m_bundle.GetNextNode();
3373  node = KdTreeNode(index);
3374  return node;
3375 }
3376 
3377 uint32_t KdTree::GetNearest(const VHACD::Vect3& pos,
3378  double radius,
3379  bool& _found) const // returns the nearest possible neighbor's index.
3380 {
3381  uint32_t ret = 0;
3382 
3383  _found = false;
3384  KdTreeFindNode found;
3385  uint32_t count = Search(pos, radius, 1, &found);
3386  if (count)
3387  {
3388  KdTreeNode* node = found.m_node;
3389  ret = node->GetIndex();
3390  _found = true;
3391  }
3392  return ret;
3393 }
3394 
3395 const std::vector<VHACD::Vertex>& KdTree::GetVertices() const { return m_vertices; }
3396 
3397 std::vector<VHACD::Vertex>&& KdTree::TakeVertices() { return std::move(m_vertices); }
3398 
3399 uint32_t KdTree::GetVCount() const { return uint32_t(m_vertices.size()); }
3400 
3401 KdTreeNode::KdTreeNode(uint32_t index) : m_index(index) {}
3402 
3403 void KdTreeNode::Add(KdTreeNode& node, Axes dim, const KdTree& tree)
3404 {
3405  Axes axis = X_AXIS;
3406  uint32_t idx = 0;
3407  switch (dim)
3408  {
3409  case X_AXIS:
3410  idx = 0;
3411  axis = Y_AXIS;
3412  break;
3413  case Y_AXIS:
3414  idx = 1;
3415  axis = Z_AXIS;
3416  break;
3417  case Z_AXIS:
3418  idx = 2;
3419  axis = X_AXIS;
3420  break;
3421  }
3422 
3423  const VHACD::Vertex& nodePosition = tree.GetPosition(node.m_index);
3424  const VHACD::Vertex& position = tree.GetPosition(m_index);
3425  if (nodePosition[idx] <= position[idx])
3426  {
3427  if (m_left)
3428  m_left->Add(node, axis, tree);
3429  else
3430  m_left = &node;
3431  }
3432  else
3433  {
3434  if (m_right)
3435  m_right->Add(node, axis, tree);
3436  else
3437  m_right = &node;
3438  }
3439 }
3440 
3441 uint32_t KdTreeNode::GetIndex() const { return m_index; }
3442 
3443 void KdTreeNode::Search(Axes axis,
3444  const VHACD::Vect3& pos,
3445  double radius,
3446  uint32_t& count,
3447  uint32_t maxObjects,
3448  KdTreeFindNode* found,
3449  const KdTree& iface)
3450 {
3451  const VHACD::Vect3 position = iface.GetPosition(m_index);
3452 
3453  const VHACD::Vect3 d = pos - position;
3454 
3455  KdTreeNode* search1 = 0;
3456  KdTreeNode* search2 = 0;
3457 
3458  uint32_t idx = 0;
3459  switch (axis)
3460  {
3461  case X_AXIS:
3462  idx = 0;
3463  axis = Y_AXIS;
3464  break;
3465  case Y_AXIS:
3466  idx = 1;
3467  axis = Z_AXIS;
3468  break;
3469  case Z_AXIS:
3470  idx = 2;
3471  axis = X_AXIS;
3472  break;
3473  }
3474 
3475  if (d[idx] <= 0) // JWR if we are to the left
3476  {
3477  search1 = m_left; // JWR then search to the left
3478  if (-d[idx] < radius) // JWR if distance to the right is less than our search radius, continue on the right
3479  // as well.
3480  search2 = m_right;
3481  }
3482  else
3483  {
3484  search1 = m_right; // JWR ok, we go down the left tree
3485  if (d[idx] < radius) // JWR if the distance from the right is less than our search radius
3486  search2 = m_left;
3487  }
3488 
3489  double r2 = radius * radius;
3490  double m = d.GetNormSquared();
3491 
3492  if (m < r2)
3493  {
3494  switch (count)
3495  {
3496  case 0:
3497  {
3498  found[count].m_node = this;
3499  found[count].m_distance = m;
3500  break;
3501  }
3502  case 1:
3503  {
3504  if (m < found[0].m_distance)
3505  {
3506  if (maxObjects == 1)
3507  {
3508  found[0].m_node = this;
3509  found[0].m_distance = m;
3510  }
3511  else
3512  {
3513  found[1] = found[0];
3514  found[0].m_node = this;
3515  found[0].m_distance = m;
3516  }
3517  }
3518  else if (maxObjects > 1)
3519  {
3520  found[1].m_node = this;
3521  found[1].m_distance = m;
3522  }
3523  break;
3524  }
3525  default:
3526  {
3527  bool inserted = false;
3528 
3529  for (uint32_t i = 0; i < count; i++)
3530  {
3531  if (m < found[i].m_distance) // if this one is closer than a pre-existing one...
3532  {
3533  // insertion sort...
3534  uint32_t scan = count;
3535  if (scan >= maxObjects)
3536  scan = maxObjects - 1;
3537  for (uint32_t j = scan; j > i; j--)
3538  {
3539  found[j] = found[j - 1];
3540  }
3541  found[i].m_node = this;
3542  found[i].m_distance = m;
3543  inserted = true;
3544  break;
3545  }
3546  }
3547 
3548  if (!inserted && count < maxObjects)
3549  {
3550  found[count].m_node = this;
3551  found[count].m_distance = m;
3552  }
3553  }
3554  break;
3555  }
3556 
3557  count++;
3558 
3559  if (count > maxObjects)
3560  {
3561  count = maxObjects;
3562  }
3563  }
3564 
3565  if (search1)
3566  search1->Search(axis, pos, radius, count, maxObjects, found, iface);
3567 
3568  if (search2)
3569  search2->Search(axis, pos, radius, count, maxObjects, found, iface);
3570 }
3571 
3572 class VertexIndex
3573 {
3574 public:
3575  VertexIndex(double granularity, bool snapToGrid);
3576 
3577  VHACD::Vect3 SnapToGrid(VHACD::Vect3 p);
3578 
3579  uint32_t GetIndex(VHACD::Vect3 p, bool& newPos);
3580 
3581  const std::vector<VHACD::Vertex>& GetVertices() const;
3582 
3583  std::vector<VHACD::Vertex>&& TakeVertices();
3584 
3585  uint32_t GetVCount() const;
3586 
3587  bool SaveAsObj(const char* fname, uint32_t tcount, uint32_t* indices)
3588  {
3589  bool ret = false;
3590 
3591  FILE* fph = fopen(fname, "wb");
3592  if (fph)
3593  {
3594  ret = true;
3595 
3596  const std::vector<VHACD::Vertex>& v = GetVertices();
3597  for (uint32_t i = 0; i < v.size(); ++i)
3598  {
3599  fprintf(fph, "v %0.9f %0.9f %0.9f\r\n", v[i].mX, v[i].mY, v[i].mZ);
3600  }
3601 
3602  for (uint32_t i = 0; i < tcount; i++)
3603  {
3604  uint32_t i1 = *indices++;
3605  uint32_t i2 = *indices++;
3606  uint32_t i3 = *indices++;
3607  fprintf(fph, "f %d %d %d\r\n", i1 + 1, i2 + 1, i3 + 1);
3608  }
3609  fclose(fph);
3610  }
3611 
3612  return ret;
3613  }
3614 
3615 private:
3616  bool m_snapToGrid : 1;
3617  double m_granularity;
3618  KdTree m_KdTree;
3619 };
3620 
3621 VertexIndex::VertexIndex(double granularity, bool snapToGrid) : m_snapToGrid(snapToGrid), m_granularity(granularity) {}
3622 
3623 VHACD::Vect3 VertexIndex::SnapToGrid(VHACD::Vect3 p)
3624 {
3625  for (int i = 0; i < 3; ++i)
3626  {
3627  double m = fmod(p[i], m_granularity);
3628  p[i] -= m;
3629  }
3630  return p;
3631 }
3632 
3633 uint32_t VertexIndex::GetIndex(VHACD::Vect3 p, bool& newPos)
3634 {
3635  uint32_t ret;
3636 
3637  newPos = false;
3638 
3639  if (m_snapToGrid)
3640  {
3641  p = SnapToGrid(p);
3642  }
3643 
3644  bool found;
3645  ret = m_KdTree.GetNearest(p, m_granularity, found);
3646  if (!found)
3647  {
3648  newPos = true;
3649  ret = m_KdTree.Add(VHACD::Vertex(p.GetX(), p.GetY(), p.GetZ()));
3650  }
3651 
3652  return ret;
3653 }
3654 
3655 const std::vector<VHACD::Vertex>& VertexIndex::GetVertices() const { return m_KdTree.GetVertices(); }
3656 
3657 std::vector<VHACD::Vertex>&& VertexIndex::TakeVertices() { return std::move(m_KdTree.TakeVertices()); }
3658 
3659 uint32_t VertexIndex::GetVCount() const { return m_KdTree.GetVCount(); }
3660 
3661 /*
3662  * A wrapper class for 3 10 bit integers packed into a 32 bit integer
3663  * Layout is [PAD][X][Y][Z]
3664  * Pad is bits 31-30, X is 29-20, Y is 19-10, and Z is 9-0
3665  */
3666 class Voxel
3667 {
3668  /*
3669  * Specify all of them for consistency
3670  */
3671  static constexpr int VoxelBitsZStart = 0;
3672  static constexpr int VoxelBitsYStart = 10;
3673  static constexpr int VoxelBitsXStart = 20;
3674  static constexpr int VoxelBitMask = 0x03FF; // bits 0 through 9 inclusive
3675 public:
3676  Voxel() = default;
3677 
3678  Voxel(uint32_t index);
3679 
3680  Voxel(uint32_t x, uint32_t y, uint32_t z);
3681 
3682  bool operator==(const Voxel& v) const;
3683 
3684  VHACD::Vector3<uint32_t> GetVoxel() const;
3685 
3686  uint32_t GetX() const;
3687  uint32_t GetY() const;
3688  uint32_t GetZ() const;
3689 
3690  uint32_t GetVoxelAddress() const;
3691 
3692 private:
3693  uint32_t m_voxel{ 0 };
3694 };
3695 
3696 Voxel::Voxel(uint32_t index) : m_voxel(index) {}
3697 
3698 Voxel::Voxel(uint32_t x, uint32_t y, uint32_t z)
3699  : m_voxel((x << VoxelBitsXStart) | (y << VoxelBitsYStart) | (z << VoxelBitsZStart))
3700 {
3701  assert(x < 1024 && "Voxel constructed with X outside of range");
3702  assert(y < 1024 && "Voxel constructed with Y outside of range");
3703  assert(z < 1024 && "Voxel constructed with Z outside of range");
3704 }
3705 
3706 bool Voxel::operator==(const Voxel& v) const { return m_voxel == v.m_voxel; }
3707 
3708 VHACD::Vector3<uint32_t> Voxel::GetVoxel() const { return VHACD::Vector3<uint32_t>(GetX(), GetY(), GetZ()); }
3709 
3710 uint32_t Voxel::GetX() const { return (m_voxel >> VoxelBitsXStart) & VoxelBitMask; }
3711 
3712 uint32_t Voxel::GetY() const { return (m_voxel >> VoxelBitsYStart) & VoxelBitMask; }
3713 
3714 uint32_t Voxel::GetZ() const { return (m_voxel >> VoxelBitsZStart) & VoxelBitMask; }
3715 
3716 uint32_t Voxel::GetVoxelAddress() const { return m_voxel; }
3717 
3718 struct SimpleMesh
3719 {
3720  std::vector<VHACD::Vertex> m_vertices;
3721  std::vector<VHACD::Triangle> m_indices;
3722 };
3723 
3724 /*======================== 0-tests ========================*/
3725 inline bool
3726 IntersectRayAABB(const VHACD::Vect3& start, const VHACD::Vect3& dir, const VHACD::BoundsAABB& bounds, double& t)
3727 {
3729  bool inside = true;
3730  VHACD::Vect3 ta(double(-1.0));
3731 
3733  for (uint32_t i = 0; i < 3; ++i)
3734  {
3735  if (start[i] < bounds.GetMin()[i])
3736  {
3737  if (dir[i] != double(0.0))
3738  ta[i] = (bounds.GetMin()[i] - start[i]) / dir[i];
3739  inside = false;
3740  }
3741  else if (start[i] > bounds.GetMax()[i])
3742  {
3743  if (dir[i] != double(0.0))
3744  ta[i] = (bounds.GetMax()[i] - start[i]) / dir[i];
3745  inside = false;
3746  }
3747  }
3748 
3750  if (inside)
3751  {
3752  t = double(0.0);
3753  return true;
3754  }
3755 
3758  uint32_t taxis;
3759  double tmax = ta.MaxCoeff(taxis);
3760 
3761  if (tmax < double(0.0))
3762  return false;
3763 
3766 
3768  double eps = double(0.0);
3769 
3770  VHACD::Vect3 hit = start + dir * tmax;
3771 
3772  if ((hit.GetX() < bounds.GetMin().GetX() - eps || hit.GetX() > bounds.GetMax().GetX() + eps) && taxis != 0)
3773  return false;
3774  if ((hit.GetY() < bounds.GetMin().GetY() - eps || hit.GetY() > bounds.GetMax().GetY() + eps) && taxis != 1)
3775  return false;
3776  if ((hit.GetZ() < bounds.GetMin().GetZ() - eps || hit.GetZ() > bounds.GetMax().GetZ() + eps) && taxis != 2)
3777  return false;
3778 
3780  t = tmax;
3781 
3782  return true;
3783 }
3784 
3785 // Moller and Trumbore's method
3786 inline bool IntersectRayTriTwoSided(const VHACD::Vect3& p,
3787  const VHACD::Vect3& dir,
3788  const VHACD::Vect3& a,
3789  const VHACD::Vect3& b,
3790  const VHACD::Vect3& c,
3791  double& t,
3792  double& u,
3793  double& v,
3794  double& w,
3795  double& sign,
3796  VHACD::Vect3* normal)
3797 {
3798  VHACD::Vect3 ab = b - a;
3799  VHACD::Vect3 ac = c - a;
3800  VHACD::Vect3 n = ab.Cross(ac);
3801 
3802  double d = -dir.Dot(n);
3803  double ood = double(1.0) / d; // No need to check for division by zero here as infinity arithmetic will save us...
3804  VHACD::Vect3 ap = p - a;
3805 
3806  t = ap.Dot(n) * ood;
3807  if (t < double(0.0))
3808  {
3809  return false;
3810  }
3811 
3812  VHACD::Vect3 e = -dir.Cross(ap);
3813  v = ac.Dot(e) * ood;
3814  if (v < double(0.0) || v > double(1.0)) // ...here...
3815  {
3816  return false;
3817  }
3818  w = -ab.Dot(e) * ood;
3819  if (w < double(0.0) || v + w > double(1.0)) // ...and here
3820  {
3821  return false;
3822  }
3823 
3824  u = double(1.0) - v - w;
3825  if (normal)
3826  {
3827  *normal = n;
3828  }
3829 
3830  sign = d;
3831 
3832  return true;
3833 }
3834 
3835 // RTCD 5.1.5, page 142
3836 inline VHACD::Vect3 ClosestPointOnTriangle(const VHACD::Vect3& a,
3837  const VHACD::Vect3& b,
3838  const VHACD::Vect3& c,
3839  const VHACD::Vect3& p,
3840  double& v,
3841  double& w)
3842 {
3843  VHACD::Vect3 ab = b - a;
3844  VHACD::Vect3 ac = c - a;
3845  VHACD::Vect3 ap = p - a;
3846 
3847  double d1 = ab.Dot(ap);
3848  double d2 = ac.Dot(ap);
3849  if (d1 <= double(0.0) && d2 <= double(0.0))
3850  {
3851  v = double(0.0);
3852  w = double(0.0);
3853  return a;
3854  }
3855 
3856  VHACD::Vect3 bp = p - b;
3857  double d3 = ab.Dot(bp);
3858  double d4 = ac.Dot(bp);
3859  if (d3 >= double(0.0) && d4 <= d3)
3860  {
3861  v = double(1.0);
3862  w = double(0.0);
3863  return b;
3864  }
3865 
3866  double vc = d1 * d4 - d3 * d2;
3867  if (vc <= double(0.0) && d1 >= double(0.0) && d3 <= double(0.0))
3868  {
3869  v = d1 / (d1 - d3);
3870  w = double(0.0);
3871  return a + v * ab;
3872  }
3873 
3874  VHACD::Vect3 cp = p - c;
3875  double d5 = ab.Dot(cp);
3876  double d6 = ac.Dot(cp);
3877  if (d6 >= double(0.0) && d5 <= d6)
3878  {
3879  v = double(0.0);
3880  w = double(1.0);
3881  return c;
3882  }
3883 
3884  double vb = d5 * d2 - d1 * d6;
3885  if (vb <= double(0.0) && d2 >= double(0.0) && d6 <= double(0.0))
3886  {
3887  v = double(0.0);
3888  w = d2 / (d2 - d6);
3889  return a + w * ac;
3890  }
3891 
3892  double va = d3 * d6 - d5 * d4;
3893  if (va <= double(0.0) && (d4 - d3) >= double(0.0) && (d5 - d6) >= double(0.0))
3894  {
3895  w = (d4 - d3) / ((d4 - d3) + (d5 - d6));
3896  v = double(1.0) - w;
3897  return b + w * (c - b);
3898  }
3899 
3900  double denom = double(1.0) / (va + vb + vc);
3901  v = vb * denom;
3902  w = vc * denom;
3903  return a + ab * v + ac * w;
3904 }
3905 
3906 class AABBTree
3907 {
3908 public:
3909  AABBTree() = default;
3910  AABBTree(AABBTree&&) = default;
3911  AABBTree& operator=(AABBTree&&) = default;
3912 
3913  AABBTree(const std::vector<VHACD::Vertex>& vertices, const std::vector<VHACD::Triangle>& indices);
3914 
3915  bool TraceRay(const VHACD::Vect3& start,
3916  const VHACD::Vect3& to,
3917  double& outT,
3918  double& faceSign,
3919  VHACD::Vect3& hitLocation) const;
3920 
3921  bool
3922  TraceRay(const VHACD::Vect3& start, const VHACD::Vect3& dir, uint32_t& insideCount, uint32_t& outsideCount) const;
3923 
3924  bool TraceRay(const VHACD::Vect3& start,
3925  const VHACD::Vect3& dir,
3926  double& outT,
3927  double& u,
3928  double& v,
3929  double& w,
3930  double& faceSign,
3931  uint32_t& faceIndex) const;
3932 
3933  VHACD::Vect3 GetCenter() const;
3934  VHACD::Vect3 GetMinExtents() const;
3935  VHACD::Vect3 GetMaxExtents() const;
3936 
3937  bool GetClosestPointWithinDistance(const VHACD::Vect3& point, double maxDistance, VHACD::Vect3& closestPoint) const;
3938 
3939 private:
3940  struct Node
3941  {
3942  union
3943  {
3944  uint32_t m_children;
3945  uint32_t m_numFaces{ 0 };
3946  };
3947 
3948  uint32_t* m_faces{ nullptr };
3949  VHACD::BoundsAABB m_extents;
3950  };
3951 
3952  struct FaceSorter
3953  {
3954  FaceSorter(const std::vector<VHACD::Vertex>& positions, const std::vector<VHACD::Triangle>& indices, uint32_t axis);
3955 
3956  bool operator()(uint32_t lhs, uint32_t rhs) const;
3957 
3958  double GetCentroid(uint32_t face) const;
3959 
3960  const std::vector<VHACD::Vertex>& m_vertices;
3961  const std::vector<VHACD::Triangle>& m_indices;
3962  uint32_t m_axis;
3963  };
3964 
3965  // partition the objects and return the number of objects in the lower partition
3966  uint32_t PartitionMedian(Node& n, uint32_t* faces, uint32_t numFaces);
3967  uint32_t PartitionSAH(Node& n, uint32_t* faces, uint32_t numFaces);
3968 
3969  void Build();
3970 
3971  void BuildRecursive(uint32_t nodeIndex, uint32_t* faces, uint32_t numFaces);
3972 
3973  void TraceRecursive(uint32_t nodeIndex,
3974  const VHACD::Vect3& start,
3975  const VHACD::Vect3& dir,
3976  double& outT,
3977  double& u,
3978  double& v,
3979  double& w,
3980  double& faceSign,
3981  uint32_t& faceIndex) const;
3982 
3983  bool GetClosestPointWithinDistance(const VHACD::Vect3& point,
3984  const double maxDis,
3985  double& dis,
3986  double& v,
3987  double& w,
3988  uint32_t& faceIndex,
3989  VHACD::Vect3& closest) const;
3990 
3991  void GetClosestPointWithinDistanceSqRecursive(uint32_t nodeIndex,
3992  const VHACD::Vect3& point,
3993  double& outDisSq,
3994  double& outV,
3995  double& outW,
3996  uint32_t& outFaceIndex,
3997  VHACD::Vect3& closest) const;
3998 
3999  VHACD::BoundsAABB CalculateFaceBounds(uint32_t* faces, uint32_t numFaces);
4000 
4001  // track the next free node
4002  uint32_t m_freeNode;
4003 
4004  const std::vector<VHACD::Vertex>* m_vertices{ nullptr };
4005  const std::vector<VHACD::Triangle>* m_indices{ nullptr };
4006 
4007  std::vector<uint32_t> m_faces;
4008  std::vector<Node> m_nodes;
4009  std::vector<VHACD::BoundsAABB> m_faceBounds;
4010 
4011  // stats
4012  uint32_t m_treeDepth{ 0 };
4013  uint32_t m_innerNodes{ 0 };
4014  uint32_t m_leafNodes{ 0 };
4015 
4016  uint32_t s_depth{ 0 };
4017 };
4018 
4019 AABBTree::FaceSorter::FaceSorter(const std::vector<VHACD::Vertex>& positions,
4020  const std::vector<VHACD::Triangle>& indices,
4021  uint32_t axis)
4022  : m_vertices(positions), m_indices(indices), m_axis(axis)
4023 {
4024 }
4025 
4026 inline bool AABBTree::FaceSorter::operator()(uint32_t lhs, uint32_t rhs) const
4027 {
4028  double a = GetCentroid(lhs);
4029  double b = GetCentroid(rhs);
4030 
4031  if (a == b)
4032  {
4033  return lhs < rhs;
4034  }
4035  else
4036  {
4037  return a < b;
4038  }
4039 }
4040 
4041 inline double AABBTree::FaceSorter::GetCentroid(uint32_t face) const
4042 {
4043  const VHACD::Vect3& a = m_vertices[m_indices[face].mI0];
4044  const VHACD::Vect3& b = m_vertices[m_indices[face].mI1];
4045  const VHACD::Vect3& c = m_vertices[m_indices[face].mI2];
4046 
4047  return (a[m_axis] + b[m_axis] + c[m_axis]) / double(3.0);
4048 }
4049 
4050 AABBTree::AABBTree(const std::vector<VHACD::Vertex>& vertices, const std::vector<VHACD::Triangle>& indices)
4051  : m_vertices(&vertices), m_indices(&indices)
4052 {
4053  Build();
4054 }
4055 
4056 bool AABBTree::TraceRay(const VHACD::Vect3& start,
4057  const VHACD::Vect3& to,
4058  double& outT,
4059  double& faceSign,
4060  VHACD::Vect3& hitLocation) const
4061 {
4062  VHACD::Vect3 dir = to - start;
4063  double distance = dir.Normalize();
4064  double u, v, w;
4065  uint32_t faceIndex;
4066  bool hit = TraceRay(start, dir, outT, u, v, w, faceSign, faceIndex);
4067  if (hit)
4068  {
4069  hitLocation = start + dir * outT;
4070  }
4071 
4072  if (hit && outT > distance)
4073  {
4074  hit = false;
4075  }
4076  return hit;
4077 }
4078 
4079 bool AABBTree::TraceRay(const VHACD::Vect3& start,
4080  const VHACD::Vect3& dir,
4081  uint32_t& insideCount,
4082  uint32_t& outsideCount) const
4083 {
4084  double outT, u, v, w, faceSign;
4085  uint32_t faceIndex;
4086  bool hit = TraceRay(start, dir, outT, u, v, w, faceSign, faceIndex);
4087  if (hit)
4088  {
4089  if (faceSign >= 0)
4090  {
4091  insideCount++;
4092  }
4093  else
4094  {
4095  outsideCount++;
4096  }
4097  }
4098  return hit;
4099 }
4100 
4101 bool AABBTree::TraceRay(const VHACD::Vect3& start,
4102  const VHACD::Vect3& dir,
4103  double& outT,
4104  double& u,
4105  double& v,
4106  double& w,
4107  double& faceSign,
4108  uint32_t& faceIndex) const
4109 {
4110  outT = FLT_MAX;
4111  TraceRecursive(0, start, dir, outT, u, v, w, faceSign, faceIndex);
4112  return (outT != FLT_MAX);
4113 }
4114 
4115 VHACD::Vect3 AABBTree::GetCenter() const { return m_nodes[0].m_extents.GetCenter(); }
4116 
4117 VHACD::Vect3 AABBTree::GetMinExtents() const { return m_nodes[0].m_extents.GetMin(); }
4118 
4119 VHACD::Vect3 AABBTree::GetMaxExtents() const { return m_nodes[0].m_extents.GetMax(); }
4120 
4121 bool AABBTree::GetClosestPointWithinDistance(const VHACD::Vect3& point,
4122  double maxDistance,
4123  VHACD::Vect3& closestPoint) const
4124 {
4125  double dis, v, w;
4126  uint32_t faceIndex;
4127  bool hit = GetClosestPointWithinDistance(point, maxDistance, dis, v, w, faceIndex, closestPoint);
4128  return hit;
4129 }
4130 
4131 // partition faces around the median face
4132 uint32_t AABBTree::PartitionMedian(Node& n, uint32_t* faces, uint32_t numFaces)
4133 {
4134  FaceSorter predicate(*m_vertices, *m_indices, n.m_extents.GetSize().LongestAxis());
4135  std::nth_element(faces, faces + numFaces / 2, faces + numFaces, predicate);
4136 
4137  return numFaces / 2;
4138 }
4139 
4140 // partition faces based on the surface area heuristic
4141 uint32_t AABBTree::PartitionSAH(Node&, uint32_t* faces, uint32_t numFaces)
4142 {
4143  uint32_t bestAxis = 0;
4144  uint32_t bestIndex = 0;
4145  double bestCost = FLT_MAX;
4146 
4147  for (uint32_t a = 0; a < 3; ++a)
4148  {
4149  // sort faces by centroids
4150  FaceSorter predicate(*m_vertices, *m_indices, a);
4151  std::sort(faces, faces + numFaces, predicate);
4152 
4153  // two passes over data to calculate upper and lower bounds
4154  std::vector<double> cumulativeLower(numFaces);
4155  std::vector<double> cumulativeUpper(numFaces);
4156 
4157  VHACD::BoundsAABB lower;
4158  VHACD::BoundsAABB upper;
4159 
4160  for (uint32_t i = 0; i < numFaces; ++i)
4161  {
4162  lower.Union(m_faceBounds[faces[i]]);
4163  upper.Union(m_faceBounds[faces[numFaces - i - 1]]);
4164 
4165  cumulativeLower[i] = lower.SurfaceArea();
4166  cumulativeUpper[numFaces - i - 1] = upper.SurfaceArea();
4167  }
4168 
4169  double invTotalSA = double(1.0) / cumulativeUpper[0];
4170 
4171  // test all split positions
4172  for (uint32_t i = 0; i < numFaces - 1; ++i)
4173  {
4174  double pBelow = cumulativeLower[i] * invTotalSA;
4175  double pAbove = cumulativeUpper[i] * invTotalSA;
4176 
4177  double cost = double(0.125) + (pBelow * i + pAbove * (numFaces - i));
4178  if (cost <= bestCost)
4179  {
4180  bestCost = cost;
4181  bestIndex = i;
4182  bestAxis = a;
4183  }
4184  }
4185  }
4186 
4187  // re-sort by best axis
4188  FaceSorter predicate(*m_vertices, *m_indices, bestAxis);
4189  std::sort(faces, faces + numFaces, predicate);
4190 
4191  return bestIndex + 1;
4192 }
4193 
4194 void AABBTree::Build()
4195 {
4196  const uint32_t numFaces = uint32_t(m_indices->size());
4197 
4198  // build initial list of faces
4199  m_faces.reserve(numFaces);
4200 
4201  // calculate bounds of each face and store
4202  m_faceBounds.reserve(numFaces);
4203 
4204  std::vector<VHACD::BoundsAABB> stack;
4205  for (uint32_t i = 0; i < numFaces; ++i)
4206  {
4207  VHACD::BoundsAABB top = CalculateFaceBounds(&i, 1);
4208 
4209  m_faces.push_back(i);
4210  m_faceBounds.push_back(top);
4211  }
4212 
4213  m_nodes.reserve(uint32_t(numFaces * double(1.5)));
4214 
4215  // allocate space for all the nodes
4216  m_freeNode = 1;
4217 
4218  // start building
4219  BuildRecursive(0, m_faces.data(), numFaces);
4220 
4221  assert(s_depth == 0);
4222 }
4223 
4224 void AABBTree::BuildRecursive(uint32_t nodeIndex, uint32_t* faces, uint32_t numFaces)
4225 {
4226  const uint32_t kMaxFacesPerLeaf = 6;
4227 
4228  // if we've run out of nodes allocate some more
4229  if (nodeIndex >= m_nodes.size())
4230  {
4231  uint32_t s = std::max(uint32_t(double(1.5) * m_nodes.size()), 512U);
4232  m_nodes.resize(s);
4233  }
4234 
4235  // a reference to the current node, need to be careful here as this reference may become invalid if array is resized
4236  Node& n = m_nodes[nodeIndex];
4237 
4238  // track max tree depth
4239  ++s_depth;
4240  m_treeDepth = std::max(m_treeDepth, s_depth);
4241 
4242  n.m_extents = CalculateFaceBounds(faces, numFaces);
4243 
4244  // calculate bounds of faces and add node
4245  if (numFaces <= kMaxFacesPerLeaf)
4246  {
4247  n.m_faces = faces;
4248  n.m_numFaces = numFaces;
4249 
4250  ++m_leafNodes;
4251  }
4252  else
4253  {
4254  ++m_innerNodes;
4255 
4256  // face counts for each branch
4257  const uint32_t leftCount = PartitionMedian(n, faces, numFaces);
4258  // const uint32_t leftCount = PartitionSAH(n, faces, numFaces);
4259  const uint32_t rightCount = numFaces - leftCount;
4260 
4261  // alloc 2 nodes
4262  m_nodes[nodeIndex].m_children = m_freeNode;
4263 
4264  // allocate two nodes
4265  m_freeNode += 2;
4266 
4267  // split faces in half and build each side recursively
4268  BuildRecursive(m_nodes[nodeIndex].m_children + 0, faces, leftCount);
4269  BuildRecursive(m_nodes[nodeIndex].m_children + 1, faces + leftCount, rightCount);
4270  }
4271 
4272  --s_depth;
4273 }
4274 
4275 void AABBTree::TraceRecursive(uint32_t nodeIndex,
4276  const VHACD::Vect3& start,
4277  const VHACD::Vect3& dir,
4278  double& outT,
4279  double& outU,
4280  double& outV,
4281  double& outW,
4282  double& faceSign,
4283  uint32_t& faceIndex) const
4284 {
4285  const Node& node = m_nodes[nodeIndex];
4286 
4287  if (node.m_faces == NULL)
4288  {
4289  // find closest node
4290  const Node& leftChild = m_nodes[node.m_children + 0];
4291  const Node& rightChild = m_nodes[node.m_children + 1];
4292 
4293  double dist[2] = { FLT_MAX, FLT_MAX };
4294 
4295  IntersectRayAABB(start, dir, leftChild.m_extents, dist[0]);
4296  IntersectRayAABB(start, dir, rightChild.m_extents, dist[1]);
4297 
4298  uint32_t closest = 0;
4299  uint32_t furthest = 1;
4300 
4301  if (dist[1] < dist[0])
4302  {
4303  closest = 1;
4304  furthest = 0;
4305  }
4306 
4307  if (dist[closest] < outT)
4308  {
4309  TraceRecursive(node.m_children + closest, start, dir, outT, outU, outV, outW, faceSign, faceIndex);
4310  }
4311 
4312  if (dist[furthest] < outT)
4313  {
4314  TraceRecursive(node.m_children + furthest, start, dir, outT, outU, outV, outW, faceSign, faceIndex);
4315  }
4316  }
4317  else
4318  {
4319  double t, u, v, w, s;
4320 
4321  for (uint32_t i = 0; i < node.m_numFaces; ++i)
4322  {
4323  uint32_t indexStart = node.m_faces[i];
4324 
4325  const VHACD::Vect3& a = (*m_vertices)[(*m_indices)[indexStart].mI0];
4326  const VHACD::Vect3& b = (*m_vertices)[(*m_indices)[indexStart].mI1];
4327  const VHACD::Vect3& c = (*m_vertices)[(*m_indices)[indexStart].mI2];
4328  if (IntersectRayTriTwoSided(start, dir, a, b, c, t, u, v, w, s, NULL))
4329  {
4330  if (t < outT)
4331  {
4332  outT = t;
4333  outU = u;
4334  outV = v;
4335  outW = w;
4336  faceSign = s;
4337  faceIndex = node.m_faces[i];
4338  }
4339  }
4340  }
4341  }
4342 }
4343 
4344 bool AABBTree::GetClosestPointWithinDistance(const VHACD::Vect3& point,
4345  const double maxDis,
4346  double& dis,
4347  double& v,
4348  double& w,
4349  uint32_t& faceIndex,
4350  VHACD::Vect3& closest) const
4351 {
4352  dis = maxDis;
4353  faceIndex = uint32_t(~0);
4354  double disSq = dis * dis;
4355 
4356  GetClosestPointWithinDistanceSqRecursive(0, point, disSq, v, w, faceIndex, closest);
4357  dis = sqrt(disSq);
4358 
4359  return (faceIndex < (~(static_cast<unsigned int>(0))));
4360 }
4361 
4362 void AABBTree::GetClosestPointWithinDistanceSqRecursive(uint32_t nodeIndex,
4363  const VHACD::Vect3& point,
4364  double& outDisSq,
4365  double& outV,
4366  double& outW,
4367  uint32_t& outFaceIndex,
4368  VHACD::Vect3& closestPoint) const
4369 {
4370  const Node& node = m_nodes[nodeIndex];
4371 
4372  if (node.m_faces == nullptr)
4373  {
4374  // find closest node
4375  const Node& leftChild = m_nodes[node.m_children + 0];
4376  const Node& rightChild = m_nodes[node.m_children + 1];
4377 
4378  // double dist[2] = { FLT_MAX, FLT_MAX };
4379  VHACD::Vect3 lp = leftChild.m_extents.ClosestPoint(point);
4380  VHACD::Vect3 rp = rightChild.m_extents.ClosestPoint(point);
4381 
4382  uint32_t closest = 0;
4383  uint32_t furthest = 1;
4384  double dcSq = (point - lp).GetNormSquared();
4385  double dfSq = (point - rp).GetNormSquared();
4386  if (dfSq < dcSq)
4387  {
4388  closest = 1;
4389  furthest = 0;
4390  std::swap(dfSq, dcSq);
4391  }
4392 
4393  if (dcSq < outDisSq)
4394  {
4395  GetClosestPointWithinDistanceSqRecursive(
4396  node.m_children + closest, point, outDisSq, outV, outW, outFaceIndex, closestPoint);
4397  }
4398 
4399  if (dfSq < outDisSq)
4400  {
4401  GetClosestPointWithinDistanceSqRecursive(
4402  node.m_children + furthest, point, outDisSq, outV, outW, outFaceIndex, closestPoint);
4403  }
4404  }
4405  else
4406  {
4407  double v, w;
4408  for (uint32_t i = 0; i < node.m_numFaces; ++i)
4409  {
4410  uint32_t indexStart = node.m_faces[i];
4411 
4412  const VHACD::Vect3& a = (*m_vertices)[(*m_indices)[indexStart].mI0];
4413  const VHACD::Vect3& b = (*m_vertices)[(*m_indices)[indexStart].mI1];
4414  const VHACD::Vect3& c = (*m_vertices)[(*m_indices)[indexStart].mI2];
4415 
4416  VHACD::Vect3 cp = ClosestPointOnTriangle(a, b, c, point, v, w);
4417  double disSq = (cp - point).GetNormSquared();
4418 
4419  if (disSq < outDisSq)
4420  {
4421  closestPoint = cp;
4422  outDisSq = disSq;
4423  outV = v;
4424  outW = w;
4425  outFaceIndex = node.m_faces[i];
4426  }
4427  }
4428  }
4429 }
4430 
4431 VHACD::BoundsAABB AABBTree::CalculateFaceBounds(uint32_t* faces, uint32_t numFaces)
4432 {
4433  VHACD::Vect3 minExtents(FLT_MAX);
4434  VHACD::Vect3 maxExtents(-FLT_MAX);
4435 
4436  // calculate face bounds
4437  for (uint32_t i = 0; i < numFaces; ++i)
4438  {
4439  VHACD::Vect3 a = (*m_vertices)[(*m_indices)[faces[i]].mI0];
4440  VHACD::Vect3 b = (*m_vertices)[(*m_indices)[faces[i]].mI1];
4441  VHACD::Vect3 c = (*m_vertices)[(*m_indices)[faces[i]].mI2];
4442 
4443  minExtents = a.CWiseMin(minExtents);
4444  maxExtents = a.CWiseMax(maxExtents);
4445 
4446  minExtents = b.CWiseMin(minExtents);
4447  maxExtents = b.CWiseMax(maxExtents);
4448 
4449  minExtents = c.CWiseMin(minExtents);
4450  maxExtents = c.CWiseMax(maxExtents);
4451  }
4452 
4453  return VHACD::BoundsAABB(minExtents, maxExtents);
4454 }
4455 
4456 enum class VoxelValue : uint8_t
4457 {
4458  PRIMITIVE_UNDEFINED = 0,
4459  PRIMITIVE_OUTSIDE_SURFACE_TOWALK = 1,
4460  PRIMITIVE_OUTSIDE_SURFACE = 2,
4461  PRIMITIVE_INSIDE_SURFACE = 3,
4462  PRIMITIVE_ON_SURFACE = 4
4463 };
4464 
4465 class Volume
4466 {
4467 public:
4468  void Voxelize(const std::vector<VHACD::Vertex>& points,
4469  const std::vector<VHACD::Triangle>& triangles,
4470  const size_t dim,
4471  FillMode fillMode,
4472  const AABBTree& aabbTree);
4473 
4474  void RaycastFill(const AABBTree& aabbTree);
4475 
4476  void SetVoxel(const size_t i, const size_t j, const size_t k, VoxelValue value);
4477 
4478  VoxelValue& GetVoxel(const size_t i, const size_t j, const size_t k);
4479 
4480  const VoxelValue& GetVoxel(const size_t i, const size_t j, const size_t k) const;
4481 
4482  const std::vector<Voxel>& GetSurfaceVoxels() const;
4483  const std::vector<Voxel>& GetInteriorVoxels() const;
4484 
4485  double GetScale() const;
4486  const VHACD::BoundsAABB& GetBounds() const;
4487  const VHACD::Vector3<uint32_t>& GetDimensions() const;
4488 
4489  VHACD::BoundsAABB m_bounds;
4490  double m_scale{ 1.0 };
4491  VHACD::Vector3<uint32_t> m_dim{ 0 };
4492  size_t m_numVoxelsOnSurface{ 0 };
4493  size_t m_numVoxelsInsideSurface{ 0 };
4494  size_t m_numVoxelsOutsideSurface{ 0 };
4495  std::vector<VoxelValue> m_data;
4496 
4497 private:
4498  void MarkOutsideSurface(const size_t i0,
4499  const size_t j0,
4500  const size_t k0,
4501  const size_t i1,
4502  const size_t j1,
4503  const size_t k1);
4504  void FillOutsideSurface();
4505 
4506  void FillInsideSurface();
4507 
4508  std::vector<VHACD::Voxel> m_surfaceVoxels;
4509  std::vector<VHACD::Voxel> m_interiorVoxels;
4510 };
4511 
4512 bool PlaneBoxOverlap(const VHACD::Vect3& normal, const VHACD::Vect3& vert, const VHACD::Vect3& maxbox)
4513 {
4514  int32_t q;
4515  VHACD::Vect3 vmin;
4516  VHACD::Vect3 vmax;
4517  double v;
4518  for (q = 0; q < 3; q++)
4519  {
4520  v = vert[q];
4521  if (normal[q] > double(0.0))
4522  {
4523  vmin[q] = -maxbox[q] - v;
4524  vmax[q] = maxbox[q] - v;
4525  }
4526  else
4527  {
4528  vmin[q] = maxbox[q] - v;
4529  vmax[q] = -maxbox[q] - v;
4530  }
4531  }
4532  if (normal.Dot(vmin) > double(0.0))
4533  return false;
4534  if (normal.Dot(vmax) >= double(0.0))
4535  return true;
4536  return false;
4537 }
4538 
4539 bool AxisTest(double a,
4540  double b,
4541  double fa,
4542  double fb,
4543  double v0,
4544  double v1,
4545  double v2,
4546  double v3,
4547  double boxHalfSize1,
4548  double boxHalfSize2)
4549 {
4550  double p0 = a * v0 + b * v1;
4551  double p1 = a * v2 + b * v3;
4552 
4553  double min = std::min(p0, p1);
4554  double max = std::max(p0, p1);
4555 
4556  double rad = fa * boxHalfSize1 + fb * boxHalfSize2;
4557  if (min > rad || max < -rad)
4558  {
4559  return false;
4560  }
4561 
4562  return true;
4563 }
4564 
4565 bool TriBoxOverlap(const VHACD::Vect3& boxCenter,
4566  const VHACD::Vect3& boxHalfSize,
4567  const VHACD::Vect3& triVer0,
4568  const VHACD::Vect3& triVer1,
4569  const VHACD::Vect3& triVer2)
4570 {
4571  /* use separating axis theorem to test overlap between triangle and box */
4572  /* need to test for overlap in these directions: */
4573  /* 1) the {x,y,z}-directions (actually, since we use the AABB of the triangle */
4574  /* we do not even need to test these) */
4575  /* 2) normal of the triangle */
4576  /* 3) crossproduct(edge from tri, {x,y,z}-direction) */
4577  /* this gives 3x3=9 more tests */
4578 
4579  VHACD::Vect3 v0 = triVer0 - boxCenter;
4580  VHACD::Vect3 v1 = triVer1 - boxCenter;
4581  VHACD::Vect3 v2 = triVer2 - boxCenter;
4582  VHACD::Vect3 e0 = v1 - v0;
4583  VHACD::Vect3 e1 = v2 - v1;
4584  VHACD::Vect3 e2 = v0 - v2;
4585 
4586  /* This is the fastest branch on Sun */
4587  /* move everything so that the boxcenter is in (0,0,0) */
4588 
4589  /* Bullet 3: */
4590  /* test the 9 tests first (this was faster) */
4591  double fex = fabs(e0[0]);
4592  double fey = fabs(e0[1]);
4593  double fez = fabs(e0[2]);
4594 
4595  /*
4596  * These should use Get*() instead of subscript for consistency, but the function calls are long enough already
4597  */
4598  if (!AxisTest(e0[2], -e0[1], fez, fey, v0[1], v0[2], v2[1], v2[2], boxHalfSize[1], boxHalfSize[2]))
4599  return 0; // X01
4600  if (!AxisTest(-e0[2], e0[0], fez, fex, v0[0], v0[2], v2[0], v2[2], boxHalfSize[0], boxHalfSize[2]))
4601  return 0; // Y02
4602  if (!AxisTest(e0[1], -e0[0], fey, fex, v1[0], v1[1], v2[0], v2[1], boxHalfSize[0], boxHalfSize[1]))
4603  return 0; // Z12
4604 
4605  fex = fabs(e1[0]);
4606  fey = fabs(e1[1]);
4607  fez = fabs(e1[2]);
4608 
4609  if (!AxisTest(e1[2], -e1[1], fez, fey, v0[1], v0[2], v2[1], v2[2], boxHalfSize[1], boxHalfSize[2]))
4610  return 0; // X01
4611  if (!AxisTest(-e1[2], e1[0], fez, fex, v0[0], v0[2], v2[0], v2[2], boxHalfSize[0], boxHalfSize[2]))
4612  return 0; // Y02
4613  if (!AxisTest(e1[1], -e1[0], fey, fex, v0[0], v0[1], v1[0], v1[1], boxHalfSize[0], boxHalfSize[2]))
4614  return 0; // Z0
4615 
4616  fex = fabs(e2[0]);
4617  fey = fabs(e2[1]);
4618  fez = fabs(e2[2]);
4619 
4620  if (!AxisTest(e2[2], -e2[1], fez, fey, v0[1], v0[2], v1[1], v1[2], boxHalfSize[1], boxHalfSize[2]))
4621  return 0; // X2
4622  if (!AxisTest(-e2[2], e2[0], fez, fex, v0[0], v0[2], v1[0], v1[2], boxHalfSize[0], boxHalfSize[2]))
4623  return 0; // Y1
4624  if (!AxisTest(e2[1], -e2[0], fey, fex, v1[0], v1[1], v2[0], v2[1], boxHalfSize[0], boxHalfSize[1]))
4625  return 0; // Z12
4626 
4627  /* Bullet 1: */
4628  /* first test overlap in the {x,y,z}-directions */
4629  /* find min, max of the triangle each direction, and test for overlap in */
4630  /* that direction -- this is equivalent to testing a minimal AABB around */
4631  /* the triangle against the AABB */
4632 
4633  /* test in 0-direction */
4634  double min = std::min({ v0.GetX(), v1.GetX(), v2.GetX() });
4635  double max = std::max({ v0.GetX(), v1.GetX(), v2.GetX() });
4636  if (min > boxHalfSize[0] || max < -boxHalfSize[0])
4637  return false;
4638 
4639  /* test in 1-direction */
4640  min = std::min({ v0.GetY(), v1.GetY(), v2.GetY() });
4641  max = std::max({ v0.GetY(), v1.GetY(), v2.GetY() });
4642  if (min > boxHalfSize[1] || max < -boxHalfSize[1])
4643  return false;
4644 
4645  /* test in getZ-direction */
4646  min = std::min({ v0.GetZ(), v1.GetZ(), v2.GetZ() });
4647  max = std::max({ v0.GetZ(), v1.GetZ(), v2.GetZ() });
4648  if (min > boxHalfSize[2] || max < -boxHalfSize[2])
4649  return false;
4650 
4651  /* Bullet 2: */
4652  /* test if the box intersects the plane of the triangle */
4653  /* compute plane equation of triangle: normal*x+d=0 */
4654  VHACD::Vect3 normal = e0.Cross(e1);
4655 
4656  if (!PlaneBoxOverlap(normal, v0, boxHalfSize))
4657  return false;
4658  return true; /* box and triangle overlaps */
4659 }
4660 
4661 void Volume::Voxelize(const std::vector<VHACD::Vertex>& points,
4662  const std::vector<VHACD::Triangle>& indices,
4663  const size_t dimensions,
4664  FillMode fillMode,
4665  const AABBTree& aabbTree)
4666 {
4667  double a = std::pow(dimensions, 0.33);
4668  size_t dim = a * double(1.5);
4669  dim = std::max(dim, size_t(32));
4670 
4671  if (points.size() == 0)
4672  {
4673  return;
4674  }
4675 
4676  m_bounds = BoundsAABB(points);
4677 
4678  VHACD::Vect3 d = m_bounds.GetSize();
4679  double r;
4680  // Equal comparison is important here to avoid taking the last branch when d[0] == d[1] with d[2] being the smallest
4681  // dimension. That would lead to dimensions in i and j to be a lot bigger than expected and make the amount of
4682  // voxels in the volume totally unmanageable.
4683  if (d[0] >= d[1] && d[0] >= d[2])
4684  {
4685  r = d[0];
4686  m_dim[0] = uint32_t(dim);
4687  m_dim[1] = uint32_t(2 + static_cast<size_t>(dim * d[1] / d[0]));
4688  m_dim[2] = uint32_t(2 + static_cast<size_t>(dim * d[2] / d[0]));
4689  }
4690  else if (d[1] >= d[0] && d[1] >= d[2])
4691  {
4692  r = d[1];
4693  m_dim[1] = uint32_t(dim);
4694  m_dim[0] = uint32_t(2 + static_cast<size_t>(dim * d[0] / d[1]));
4695  m_dim[2] = uint32_t(2 + static_cast<size_t>(dim * d[2] / d[1]));
4696  }
4697  else
4698  {
4699  r = d[2];
4700  m_dim[2] = uint32_t(dim);
4701  m_dim[0] = uint32_t(2 + static_cast<size_t>(dim * d[0] / d[2]));
4702  m_dim[1] = uint32_t(2 + static_cast<size_t>(dim * d[1] / d[2]));
4703  }
4704 
4705  m_scale = r / (dim - 1);
4706  double invScale = (dim - 1) / r;
4707 
4708  m_data = std::vector<VoxelValue>(m_dim[0] * m_dim[1] * m_dim[2], VoxelValue::PRIMITIVE_UNDEFINED);
4709  m_numVoxelsOnSurface = 0;
4710  m_numVoxelsInsideSurface = 0;
4711  m_numVoxelsOutsideSurface = 0;
4712 
4713  VHACD::Vect3 p[3];
4714  VHACD::Vect3 boxcenter;
4715  VHACD::Vect3 pt;
4716  const VHACD::Vect3 boxhalfsize(double(0.5));
4717  for (size_t t = 0; t < indices.size(); ++t)
4718  {
4719  size_t i0, j0, k0;
4720  size_t i1, j1, k1;
4721  VHACD::Vector3<uint32_t> tri = indices[t];
4722  for (int32_t c = 0; c < 3; ++c)
4723  {
4724  pt = points[tri[c]];
4725 
4726  p[c] = (pt - m_bounds.GetMin()) * invScale;
4727 
4728  size_t i = static_cast<size_t>(p[c][0] + double(0.5));
4729  size_t j = static_cast<size_t>(p[c][1] + double(0.5));
4730  size_t k = static_cast<size_t>(p[c][2] + double(0.5));
4731 
4732  assert(i < m_dim[0] && j < m_dim[1] && k < m_dim[2]);
4733 
4734  if (c == 0)
4735  {
4736  i0 = i1 = i;
4737  j0 = j1 = j;
4738  k0 = k1 = k;
4739  }
4740  else
4741  {
4742  i0 = std::min(i0, i);
4743  j0 = std::min(j0, j);
4744  k0 = std::min(k0, k);
4745 
4746  i1 = std::max(i1, i);
4747  j1 = std::max(j1, j);
4748  k1 = std::max(k1, k);
4749  }
4750  }
4751  if (i0 > 0)
4752  --i0;
4753  if (j0 > 0)
4754  --j0;
4755  if (k0 > 0)
4756  --k0;
4757  if (i1 < m_dim[0])
4758  ++i1;
4759  if (j1 < m_dim[1])
4760  ++j1;
4761  if (k1 < m_dim[2])
4762  ++k1;
4763  for (size_t i_id = i0; i_id < i1; ++i_id)
4764  {
4765  boxcenter[0] = uint32_t(i_id);
4766  for (size_t j_id = j0; j_id < j1; ++j_id)
4767  {
4768  boxcenter[1] = uint32_t(j_id);
4769  for (size_t k_id = k0; k_id < k1; ++k_id)
4770  {
4771  boxcenter[2] = uint32_t(k_id);
4772  bool res = TriBoxOverlap(boxcenter, boxhalfsize, p[0], p[1], p[2]);
4773  VoxelValue& value = GetVoxel(i_id, j_id, k_id);
4774  if (res && value == VoxelValue::PRIMITIVE_UNDEFINED)
4775  {
4776  value = VoxelValue::PRIMITIVE_ON_SURFACE;
4777  ++m_numVoxelsOnSurface;
4778  m_surfaceVoxels.emplace_back(uint32_t(i_id), uint32_t(j_id), uint32_t(k_id));
4779  }
4780  }
4781  }
4782  }
4783  }
4784 
4785  if (fillMode == FillMode::SURFACE_ONLY)
4786  {
4787  const size_t i0_local = m_dim[0];
4788  const size_t j0_local = m_dim[1];
4789  const size_t k0_local = m_dim[2];
4790  for (size_t i_id = 0; i_id < i0_local; ++i_id)
4791  {
4792  for (size_t j_id = 0; j_id < j0_local; ++j_id)
4793  {
4794  for (size_t k_id = 0; k_id < k0_local; ++k_id)
4795  {
4796  const VoxelValue& voxel = GetVoxel(i_id, j_id, k_id);
4797  if (voxel != VoxelValue::PRIMITIVE_ON_SURFACE)
4798  {
4799  SetVoxel(i_id, j_id, k_id, VoxelValue::PRIMITIVE_OUTSIDE_SURFACE);
4800  }
4801  }
4802  }
4803  }
4804  }
4805  else if (fillMode == FillMode::FLOOD_FILL)
4806  {
4807  /*
4808  * Marking the outside edges of the voxel cube to be outside surfaces to walk
4809  */
4810  MarkOutsideSurface(0, 0, 0, m_dim[0], m_dim[1], 1);
4811  MarkOutsideSurface(0, 0, m_dim[2] - 1, m_dim[0], m_dim[1], m_dim[2]);
4812  MarkOutsideSurface(0, 0, 0, m_dim[0], 1, m_dim[2]);
4813  MarkOutsideSurface(0, m_dim[1] - 1, 0, m_dim[0], m_dim[1], m_dim[2]);
4814  MarkOutsideSurface(0, 0, 0, 1, m_dim[1], m_dim[2]);
4815  MarkOutsideSurface(m_dim[0] - 1, 0, 0, m_dim[0], m_dim[1], m_dim[2]);
4816  FillOutsideSurface();
4817  FillInsideSurface();
4818  }
4819  else if (fillMode == FillMode::RAYCAST_FILL)
4820  {
4821  RaycastFill(aabbTree);
4822  }
4823 }
4824 
4825 void Volume::RaycastFill(const AABBTree& aabbTree)
4826 {
4827  const uint32_t i0 = m_dim[0];
4828  const uint32_t j0 = m_dim[1];
4829  const uint32_t k0 = m_dim[2];
4830 
4831  size_t maxSize = i0 * j0 * k0;
4832 
4833  std::vector<Voxel> temp;
4834  temp.reserve(maxSize);
4835  uint32_t count{ 0 };
4836  m_numVoxelsInsideSurface = 0;
4837  for (uint32_t i = 0; i < i0; ++i)
4838  {
4839  for (uint32_t j = 0; j < j0; ++j)
4840  {
4841  for (uint32_t k = 0; k < k0; ++k)
4842  {
4843  VoxelValue& voxel = GetVoxel(i, j, k);
4844  if (voxel != VoxelValue::PRIMITIVE_ON_SURFACE)
4845  {
4846  VHACD::Vect3 start = VHACD::Vect3(i, j, k) * m_scale + m_bounds.GetMin();
4847 
4848  uint32_t insideCount = 0;
4849  uint32_t outsideCount = 0;
4850 
4851  VHACD::Vect3 directions[6] = {
4852  VHACD::Vect3(1, 0, 0), VHACD::Vect3(-1, 0, 0), // this was 1, 0, 0 in the original code, but looks wrong
4853  VHACD::Vect3(0, 1, 0), VHACD::Vect3(0, -1, 0), VHACD::Vect3(0, 0, 1), VHACD::Vect3(0, 0, -1)
4854  };
4855 
4856  for (uint32_t r = 0; r < 6; r++)
4857  {
4858  aabbTree.TraceRay(start, directions[r], insideCount, outsideCount);
4859  // Early out if we hit the outside of the mesh
4860  if (outsideCount)
4861  {
4862  break;
4863  }
4864  // Early out if we accumulated 3 inside hits
4865  if (insideCount >= 3)
4866  {
4867  break;
4868  }
4869  }
4870 
4871  if (outsideCount == 0 && insideCount >= 3)
4872  {
4873  voxel = VoxelValue::PRIMITIVE_INSIDE_SURFACE;
4874  temp.emplace_back(i, j, k);
4875  count++;
4876  m_numVoxelsInsideSurface++;
4877  }
4878  else
4879  {
4880  voxel = VoxelValue::PRIMITIVE_OUTSIDE_SURFACE;
4881  }
4882  }
4883  }
4884  }
4885  }
4886 
4887  if (count)
4888  {
4889  m_interiorVoxels = std::move(temp);
4890  }
4891 }
4892 
4893 void Volume::SetVoxel(const size_t i, const size_t j, const size_t k, VoxelValue value)
4894 {
4895  assert(i < m_dim[0]);
4896  assert(j < m_dim[1]);
4897  assert(k < m_dim[2]);
4898 
4899  m_data[k + j * m_dim[2] + i * m_dim[1] * m_dim[2]] = value;
4900 }
4901 
4902 VoxelValue& Volume::GetVoxel(const size_t i, const size_t j, const size_t k)
4903 {
4904  assert(i < m_dim[0]);
4905  assert(j < m_dim[1]);
4906  assert(k < m_dim[2]);
4907  return m_data[k + j * m_dim[2] + i * m_dim[1] * m_dim[2]];
4908 }
4909 
4910 const VoxelValue& Volume::GetVoxel(const size_t i, const size_t j, const size_t k) const
4911 {
4912  assert(i < m_dim[0]);
4913  assert(j < m_dim[1]);
4914  assert(k < m_dim[2]);
4915  return m_data[k + j * m_dim[2] + i * m_dim[1] * m_dim[2]];
4916 }
4917 
4918 const std::vector<Voxel>& Volume::GetSurfaceVoxels() const { return m_surfaceVoxels; }
4919 
4920 const std::vector<Voxel>& Volume::GetInteriorVoxels() const { return m_interiorVoxels; }
4921 
4922 double Volume::GetScale() const { return m_scale; }
4923 
4924 const VHACD::BoundsAABB& Volume::GetBounds() const { return m_bounds; }
4925 
4926 const VHACD::Vector3<uint32_t>& Volume::GetDimensions() const { return m_dim; }
4927 
4928 void Volume::MarkOutsideSurface(const size_t i0,
4929  const size_t j0,
4930  const size_t k0,
4931  const size_t i1,
4932  const size_t j1,
4933  const size_t k1)
4934 {
4935  for (size_t i = i0; i < i1; ++i)
4936  {
4937  for (size_t j = j0; j < j1; ++j)
4938  {
4939  for (size_t k = k0; k < k1; ++k)
4940  {
4941  VoxelValue& v = GetVoxel(i, j, k);
4942  if (v == VoxelValue::PRIMITIVE_UNDEFINED)
4943  {
4944  v = VoxelValue::PRIMITIVE_OUTSIDE_SURFACE_TOWALK;
4945  }
4946  }
4947  }
4948  }
4949 }
4950 
4951 inline void WalkForward(int64_t start, int64_t end, VoxelValue* ptr, int64_t stride, int64_t maxDistance)
4952 {
4953  for (int64_t i = start, count = 0; count < maxDistance && i < end && *ptr == VoxelValue::PRIMITIVE_UNDEFINED;
4954  ++i, ptr += stride, ++count)
4955  {
4956  *ptr = VoxelValue::PRIMITIVE_OUTSIDE_SURFACE_TOWALK;
4957  }
4958 }
4959 
4960 inline void WalkBackward(int64_t start, int64_t end, VoxelValue* ptr, int64_t stride, int64_t maxDistance)
4961 {
4962  for (int64_t i = start, count = 0; count < maxDistance && i >= end && *ptr == VoxelValue::PRIMITIVE_UNDEFINED;
4963  --i, ptr -= stride, ++count)
4964  {
4965  *ptr = VoxelValue::PRIMITIVE_OUTSIDE_SURFACE_TOWALK;
4966  }
4967 }
4968 
4969 void Volume::FillOutsideSurface()
4970 {
4971  size_t voxelsWalked = 0;
4972  const int64_t i0 = m_dim[0];
4973  const int64_t j0 = m_dim[1];
4974  const int64_t k0 = m_dim[2];
4975 
4976  // Avoid striding too far in each direction to stay in L1 cache as much as possible.
4977  // The cache size required for the walk is roughly (4 * walkDistance * 64) since
4978  // the k direction doesn't count as it's walking byte per byte directly in a cache lines.
4979  // ~16k is required for a walk distance of 64 in each directions.
4980  const size_t walkDistance = 64;
4981 
4982  // using the stride directly instead of calling GetVoxel for each iterations saves
4983  // a lot of multiplications and pipeline stalls due to data dependencies on imul.
4984  const size_t istride = &GetVoxel(1, 0, 0) - &GetVoxel(0, 0, 0);
4985  const size_t jstride = &GetVoxel(0, 1, 0) - &GetVoxel(0, 0, 0);
4986  const size_t kstride = &GetVoxel(0, 0, 1) - &GetVoxel(0, 0, 0);
4987 
4988  // It might seem counter intuitive to go over the whole voxel range multiple times
4989  // but since we do the run in memory order, it leaves us with far fewer cache misses
4990  // than a BFS algorithm and it has the additional benefit of not requiring us to
4991  // store and manipulate a fifo for recursion that might become huge when the number
4992  // of voxels is large.
4993  // This will outperform the BFS algorithm by several orders of magnitude in practice.
4994  do
4995  {
4996  voxelsWalked = 0;
4997  for (int64_t i = 0; i < i0; ++i)
4998  {
4999  for (int64_t j = 0; j < j0; ++j)
5000  {
5001  for (int64_t k = 0; k < k0; ++k)
5002  {
5003  VoxelValue& voxel = GetVoxel(i, j, k);
5004  if (voxel == VoxelValue::PRIMITIVE_OUTSIDE_SURFACE_TOWALK)
5005  {
5006  voxelsWalked++;
5007  voxel = VoxelValue::PRIMITIVE_OUTSIDE_SURFACE;
5008 
5009  // walk in each direction to mark other voxel that should be walked.
5010  // this will generate a 3d pattern that will help the overall
5011  // algorithm converge faster while remaining cache friendly.
5012  WalkForward(k + 1, k0, &voxel + kstride, kstride, walkDistance);
5013  WalkBackward(k - 1, 0, &voxel - kstride, kstride, walkDistance);
5014 
5015  WalkForward(j + 1, j0, &voxel + jstride, jstride, walkDistance);
5016  WalkBackward(j - 1, 0, &voxel - jstride, jstride, walkDistance);
5017 
5018  WalkForward(i + 1, i0, &voxel + istride, istride, walkDistance);
5019  WalkBackward(i - 1, 0, &voxel - istride, istride, walkDistance);
5020  }
5021  }
5022  }
5023  }
5024 
5025  m_numVoxelsOutsideSurface += voxelsWalked;
5026  } while (voxelsWalked != 0);
5027 }
5028 
5029 void Volume::FillInsideSurface()
5030 {
5031  const uint32_t i0 = uint32_t(m_dim[0]);
5032  const uint32_t j0 = uint32_t(m_dim[1]);
5033  const uint32_t k0 = uint32_t(m_dim[2]);
5034 
5035  size_t maxSize = i0 * j0 * k0;
5036 
5037  std::vector<Voxel> temp;
5038  temp.reserve(maxSize);
5039  uint32_t count{ 0 };
5040 
5041  for (uint32_t i = 0; i < i0; ++i)
5042  {
5043  for (uint32_t j = 0; j < j0; ++j)
5044  {
5045  for (uint32_t k = 0; k < k0; ++k)
5046  {
5047  VoxelValue& v = GetVoxel(i, j, k);
5048  if (v == VoxelValue::PRIMITIVE_UNDEFINED)
5049  {
5050  v = VoxelValue::PRIMITIVE_INSIDE_SURFACE;
5051  temp.emplace_back(i, j, k);
5052  count++;
5053  ++m_numVoxelsInsideSurface;
5054  }
5055  }
5056  }
5057  }
5058 
5059  if (count)
5060  {
5061  m_interiorVoxels = std::move(temp);
5062  }
5063 }
5064 
5065 //******************************************************************************************
5066 // ShrinkWrap helper class
5067 //******************************************************************************************
5068 // This is a code snippet which 'shrinkwraps' a convex hull
5069 // to a source mesh.
5070 //
5071 // It is a somewhat complicated algorithm. It works as follows:
5072 //
5073 // * Step #1 : Compute the mean unit normal vector for each vertex in the convex hull
5074 // * Step #2 : For each vertex in the conex hull we project is slightly outwards along the mean normal vector
5075 // * Step #3 : We then raycast from this slightly extruded point back into the opposite direction of the mean normal
5076 // vector
5077 // resulting in a raycast from slightly beyond the vertex in the hull into the source mesh we are trying
5078 // to 'shrink wrap' against
5079 // * Step #4 : If the raycast fails we leave the original vertex alone
5080 // * Step #5 : If the raycast hits a backface we leave the original vertex alone
5081 // * Step #6 : If the raycast hits too far away (no more than a certain threshold distance) we live it alone
5082 // * Step #7 : If the point we hit on the source mesh is not still within the convex hull, we reject it.
5083 // * Step #8 : If all of the previous conditions are met, then we take the raycast hit location as the 'new position'
5084 // * Step #9 : Once all points have been projected, if possible, we need to recompute the convex hull again based on
5085 // these shrinkwrapped points
5086 // * Step #10 : In theory that should work.. let's see...
5087 
5088 //***********************************************************************************************
5089 // QuickHull implementation
5090 //***********************************************************************************************
5091 
5093 // Quickhull base class holding the hull during construction
5095 class QuickHull
5096 {
5097 public:
5098  uint32_t ComputeConvexHull(const std::vector<VHACD::Vertex>& vertices, uint32_t maxHullVertices);
5099 
5100  const std::vector<VHACD::Vertex>& GetVertices() const;
5101  const std::vector<VHACD::Triangle>& GetIndices() const;
5102 
5103 private:
5104  std::vector<VHACD::Vertex> m_vertices;
5105  std::vector<VHACD::Triangle> m_indices;
5106 };
5107 
5108 uint32_t QuickHull::ComputeConvexHull(const std::vector<VHACD::Vertex>& vertices, uint32_t maxHullVertices)
5109 {
5110  m_indices.clear();
5111 
5112  VHACD::ConvexHull ch(vertices, double(0.0001), maxHullVertices);
5113 
5114  auto& vlist = ch.GetVertexPool();
5115  if (!vlist.empty())
5116  {
5117  size_t vcount = vlist.size();
5118  m_vertices.resize(vcount);
5119  std::copy(vlist.begin(), vlist.end(), m_vertices.begin());
5120  }
5121 
5122  for (std::list<ConvexHullFace>::const_iterator node = ch.GetList().begin(); node != ch.GetList().end(); ++node)
5123  {
5124  const VHACD::ConvexHullFace& face = *node;
5125  m_indices.emplace_back(face.m_index[0], face.m_index[1], face.m_index[2]);
5126  }
5127 
5128  return uint32_t(m_indices.size());
5129 }
5130 
5131 const std::vector<VHACD::Vertex>& QuickHull::GetVertices() const { return m_vertices; }
5132 
5133 const std::vector<VHACD::Triangle>& QuickHull::GetIndices() const { return m_indices; }
5134 
5135 //******************************************************************************************
5136 // Implementation of the ShrinkWrap function
5137 //******************************************************************************************
5138 
5139 void ShrinkWrap(SimpleMesh& sourceConvexHull,
5140  const AABBTree& aabbTree,
5141  uint32_t maxHullVertexCount,
5142  double distanceThreshold,
5143  bool doShrinkWrap)
5144 {
5145  std::vector<VHACD::Vertex> verts; // New verts for the new convex hull
5146  verts.reserve(sourceConvexHull.m_vertices.size());
5147  // Examine each vertex and see if it is within the voxel distance.
5148  // If it is, then replace the point with the shrinkwrapped / projected point
5149  for (uint32_t j = 0; j < sourceConvexHull.m_vertices.size(); j++)
5150  {
5151  VHACD::Vertex& p = sourceConvexHull.m_vertices[j];
5152  if (doShrinkWrap)
5153  {
5154  VHACD::Vect3 closest;
5155  if (aabbTree.GetClosestPointWithinDistance(p, distanceThreshold, closest))
5156  {
5157  p = closest;
5158  }
5159  }
5160  verts.emplace_back(p);
5161  }
5162  // Final step is to recompute the convex hull
5163  VHACD::QuickHull qh;
5164  uint32_t tcount = qh.ComputeConvexHull(verts, maxHullVertexCount);
5165  if (tcount)
5166  {
5167  sourceConvexHull.m_vertices = qh.GetVertices();
5168  sourceConvexHull.m_indices = qh.GetIndices();
5169  }
5170 }
5171 
5172 //********************************************************************************************************************
5173 
5174 #if !VHACD_DISABLE_THREADING
5175 
5176 //********************************************************************************************************************
5177 // Definition of the ThreadPool
5178 //********************************************************************************************************************
5179 
5180 class ThreadPool
5181 {
5182 public:
5183  ThreadPool();
5184  ThreadPool(int worker);
5185  ~ThreadPool();
5186  template <typename F, typename... Args>
5187  auto enqueue(F&& f, Args&&... args)
5188 #ifndef __cpp_lib_is_invocable
5189  -> std::future<typename std::result_of<F(Args...)>::type>;
5190 #else
5191  -> std::future<typename std::invoke_result_t<F, Args...>>;
5192 #endif
5193 private:
5194  std::vector<std::thread> workers;
5195  std::deque<std::function<void()>> tasks;
5196  std::mutex task_mutex;
5197  std::condition_variable cv;
5198  bool closed;
5199  int count;
5200 };
5201 
5202 ThreadPool::ThreadPool() : ThreadPool(1) {}
5203 
5204 ThreadPool::ThreadPool(int worker) : closed(false), count(0)
5205 {
5206  workers.reserve(worker);
5207  for (int i = 0; i < worker; i++)
5208  {
5209  workers.emplace_back([this] {
5210  std::unique_lock<std::mutex> lock(this->task_mutex);
5211  while (true)
5212  {
5213  while (this->tasks.empty())
5214  {
5215  if (this->closed)
5216  {
5217  return;
5218  }
5219  this->cv.wait(lock);
5220  }
5221  auto task = this->tasks.front();
5222  this->tasks.pop_front();
5223  lock.unlock();
5224  task();
5225  lock.lock();
5226  }
5227  });
5228  }
5229 }
5230 
5231 template <typename F, typename... Args>
5232 auto ThreadPool::enqueue(F&& f, Args&&... args)
5233 #ifndef __cpp_lib_is_invocable
5234  -> std::future<typename std::result_of<F(Args...)>::type>
5235 #else
5236  -> std::future<typename std::invoke_result_t<F, Args...>>
5237 #endif
5238 {
5239 #ifndef __cpp_lib_is_invocable
5240  using return_type = typename std::result_of<F(Args...)>::type;
5241 #else
5242  using return_type = typename std::invoke_result_t<F, Args...>;
5243 #endif
5244  auto task =
5245  std::make_shared<std::packaged_task<return_type()>>(std::bind(std::forward<F>(f), std::forward<Args>(args)...));
5246  auto result = task->get_future();
5247 
5248  {
5249  std::unique_lock<std::mutex> lock(task_mutex);
5250  if (!closed)
5251  {
5252  tasks.emplace_back([task] { (*task)(); });
5253  cv.notify_one();
5254  }
5255  }
5256 
5257  return result;
5258 }
5259 
5260 ThreadPool::~ThreadPool()
5261 {
5262  {
5263  std::unique_lock<std::mutex> lock(task_mutex);
5264  closed = true;
5265  }
5266  cv.notify_all();
5267  for (auto&& worker : workers)
5268  {
5269  worker.join();
5270  }
5271 }
5272 #endif
5273 
5274 enum class Stages
5275 {
5276  COMPUTE_BOUNDS_OF_INPUT_MESH,
5277  REINDEXING_INPUT_MESH,
5278  CREATE_RAYCAST_MESH,
5279  VOXELIZING_INPUT_MESH,
5280  BUILD_INITIAL_CONVEX_HULL,
5281  PERFORMING_DECOMPOSITION,
5282  INITIALIZING_CONVEX_HULLS_FOR_MERGING,
5283  COMPUTING_COST_MATRIX,
5284  MERGING_CONVEX_HULLS,
5285  FINALIZING_RESULTS,
5286  NUM_STAGES
5287 };
5288 
5289 class VHACDCallbacks
5290 {
5291 public:
5292  virtual void ProgressUpdate(Stages stage, double stageProgress, const char* operation) = 0;
5293  virtual bool IsCanceled() const = 0;
5294 
5295  virtual ~VHACDCallbacks() = default;
5296 };
5297 
5298 enum class SplitAxis
5299 {
5300  X_AXIS_NEGATIVE,
5301  X_AXIS_POSITIVE,
5302  Y_AXIS_NEGATIVE,
5303  Y_AXIS_POSITIVE,
5304  Z_AXIS_NEGATIVE,
5305  Z_AXIS_POSITIVE,
5306 };
5307 
5308 // This class represents a collection of voxels, the convex hull
5309 // which surrounds them, and a triangle mesh representation of those voxels
5310 class VoxelHull
5311 {
5312 public:
5313  // This method constructs a new VoxelHull based on a plane split of the parent
5314  // convex hull
5315  VoxelHull(const VoxelHull& parent, SplitAxis axis, uint32_t splitLoc);
5316 
5317  // Here we construct the initial convex hull around the
5318  // entire voxel set
5319  VoxelHull(Volume& voxels, const IVHACD::Parameters& params, VHACDCallbacks* callbacks);
5320 
5321  ~VoxelHull() = default;
5322 
5323  // Helper method to refresh the min/max voxel bounding region
5324  void MinMaxVoxelRegion(const Voxel& v);
5325 
5326  void BuildRaycastMesh();
5327 
5328  // We now compute the convex hull relative to a triangle mesh generated
5329  // from the voxels
5330  void ComputeConvexHull();
5331 
5332  // Returns true if this convex hull should be considered done
5333  bool IsComplete();
5334 
5335  // Convert a voxel position into it's correct double precision location
5336  VHACD::Vect3
5337  GetPoint(const int32_t x, const int32_t y, const int32_t z, const double scale, const VHACD::Vect3& bmin) const;
5338 
5339  // Sees if we have already got an index for this voxel position.
5340  // If the voxel position has already been indexed, we just return
5341  // that index value.
5342  // If not, then we convert it into the floating point position and
5343  // add it to the index map
5344  uint32_t GetVertexIndex(const VHACD::Vector3<uint32_t>& p);
5345 
5346  // This method will convert the voxels into an actual indexed triangle mesh of boxes
5347  // This serves two purposes.
5348  // The primary purpose is so that when we compute a convex hull it considered all of the points
5349  // for each voxel, not just the center point. If you don't do this, then the hulls don't fit the
5350  // mesh accurately enough.
5351  // The second reason we convert it into a triangle mesh is so that we can do raycasting against it
5352  // to search for the best splitting plane fairly quickly. That algorithm will be discussed in the
5353  // method which computes the best splitting plane.
5354  void BuildVoxelMesh();
5355 
5356  // Convert a single voxel position into an actual 3d box mesh comprised
5357  // of 12 triangles
5358  void AddVoxelBox(const Voxel& v);
5359 
5360  // Add the triangle represented by these 3 indices into the 'box' set of vertices
5361  // to the output mesh
5362  void AddTri(const std::array<VHACD::Vector3<uint32_t>, 8>& box, uint32_t i1, uint32_t i2, uint32_t i3);
5363 
5364  // Here we convert from voxel space to a 3d position, index it, and add
5365  // the triangle positions and indices for the output mesh
5366  void AddTriangle(const VHACD::Vector3<uint32_t>& p1,
5367  const VHACD::Vector3<uint32_t>& p2,
5368  const VHACD::Vector3<uint32_t>& p3);
5369 
5370  // When computing the split plane, we start by simply
5371  // taking the midpoint of the longest side. However,
5372  // we can also search the surface and look for the greatest
5373  // spot of concavity and use that as the split location.
5374  // This will make the convex decomposition more efficient
5375  // as it will tend to cut across the greatest point of
5376  // concavity on the surface.
5377  SplitAxis ComputeSplitPlane(uint32_t& location);
5378 
5379  VHACD::Vect3 GetPosition(const VHACD::Vector3<int32_t>& ip) const;
5380 
5381  double Raycast(const VHACD::Vector3<int32_t>& p1, const VHACD::Vector3<int32_t>& p2) const;
5382 
5383  bool FindConcavity(uint32_t idx, uint32_t& splitLoc);
5384 
5385  // Finding the greatest area of concavity..
5386  bool FindConcavityX(uint32_t& splitLoc);
5387 
5388  // Finding the greatest area of concavity..
5389  bool FindConcavityY(uint32_t& splitLoc);
5390 
5391  // Finding the greatest area of concavity..
5392  bool FindConcavityZ(uint32_t& splitLoc);
5393 
5394  // This operation is performed in a background thread.
5395  // It splits the voxels by a plane
5396  void PerformPlaneSplit();
5397 
5398  // Used only for debugging. Saves the voxelized mesh to disk
5399  // Optionally saves the original source mesh as well for comparison
5400  void SaveVoxelMesh(const SimpleMesh& inputMesh, bool saveVoxelMesh, bool saveSourceMesh);
5401 
5402  void SaveOBJ(const char* fname, const VoxelHull* h);
5403 
5404  void SaveOBJ(const char* fname);
5405 
5406 private:
5407  void WriteOBJ(FILE* fph,
5408  const std::vector<VHACD::Vertex>& vertices,
5409  const std::vector<VHACD::Triangle>& indices,
5410  uint32_t baseIndex);
5411 
5412 public:
5413  SplitAxis m_axis{ SplitAxis::X_AXIS_NEGATIVE };
5414  Volume* m_voxels{ nullptr }; // The voxelized data set
5415  double m_voxelScale{ 0 }; // Size of a single voxel
5416  double m_voxelScaleHalf{ 0 }; // 1/2 of the size of a single voxel
5417  VHACD::BoundsAABB m_voxelBounds;
5418  VHACD::Vect3 m_voxelAdjust; // Minimum coordinates of the voxel space, with adjustment
5419  uint32_t m_depth{ 0 }; // How deep in the recursion of the binary tree this hull is
5420  uint32_t m_index{ 0 }; // Each convex hull is given a unique id to distinguish it from the others
5421  double m_volumeError{ 0 }; // The percentage error from the convex hull volume vs. the voxel volume
5422  double m_voxelVolume{ 0 }; // The volume of the voxels
5423  double m_hullVolume{ 0 }; // The volume of the enclosing convex hull
5424 
5425  std::unique_ptr<IVHACD::ConvexHull> m_convexHull{ nullptr }; // The convex hull which encloses this set of voxels.
5426  std::vector<Voxel> m_surfaceVoxels; // The voxels which are on the surface of the source mesh.
5427  std::vector<Voxel> m_newSurfaceVoxels; // Voxels which are on the surface as a result of a plane split
5428  std::vector<Voxel> m_interiorVoxels; // Voxels which are part of the interior of the hull
5429 
5430  std::unique_ptr<VoxelHull> m_hullA{ nullptr }; // hull resulting from one side of the plane split
5431  std::unique_ptr<VoxelHull> m_hullB{ nullptr }; // hull resulting from the other side of the plane split
5432 
5433  // Defines the coordinates this convex hull comprises within the voxel volume
5434  // of the entire source
5435  VHACD::Vector3<uint32_t> m_1{ 0 };
5436  VHACD::Vector3<uint32_t> m_2{ 0 };
5437  AABBTree m_AABBTree;
5438  std::unordered_map<uint32_t, uint32_t> m_voxelIndexMap; // Maps from a voxel coordinate space into a vertex index
5439  // space
5440  std::vector<VHACD::Vertex> m_vertices;
5441  std::vector<VHACD::Triangle> m_indices;
5442  static uint32_t m_voxelHullCount;
5443  IVHACD::Parameters m_params;
5444  VHACDCallbacks* m_callbacks{ nullptr };
5445 };
5446 
5447 uint32_t VoxelHull::m_voxelHullCount = 0;
5448 
5449 VoxelHull::VoxelHull(const VoxelHull& parent, SplitAxis axis, uint32_t splitLoc)
5450  : m_axis(axis)
5451  , m_voxels(parent.m_voxels)
5452  , m_voxelScale(m_voxels->GetScale())
5453  , m_voxelScaleHalf(m_voxelScale * double(0.5))
5454  , m_voxelBounds(m_voxels->GetBounds())
5455  , m_voxelAdjust(m_voxelBounds.GetMin() - m_voxelScaleHalf)
5456  , m_depth(parent.m_depth + 1)
5457  , m_index(++m_voxelHullCount)
5458  , m_1(parent.m_1)
5459  , m_2(parent.m_2)
5460  , m_params(parent.m_params)
5461 {
5462  // Default copy the voxel region from the parent, but values will
5463  // be adjusted next based on the split axis and location
5464  switch (m_axis)
5465  {
5466  case SplitAxis::X_AXIS_NEGATIVE:
5467  m_2.GetX() = splitLoc;
5468  break;
5469  case SplitAxis::X_AXIS_POSITIVE:
5470  m_1.GetX() = splitLoc + 1;
5471  break;
5472  case SplitAxis::Y_AXIS_NEGATIVE:
5473  m_2.GetY() = splitLoc;
5474  break;
5475  case SplitAxis::Y_AXIS_POSITIVE:
5476  m_1.GetY() = splitLoc + 1;
5477  break;
5478  case SplitAxis::Z_AXIS_NEGATIVE:
5479  m_2.GetZ() = splitLoc;
5480  break;
5481  case SplitAxis::Z_AXIS_POSITIVE:
5482  m_1.GetZ() = splitLoc + 1;
5483  break;
5484  }
5485 
5486  // First, we copy all of the interior voxels from our parent
5487  // which intersect our region
5488  for (auto& i : parent.m_interiorVoxels)
5489  {
5490  VHACD::Vector3<uint32_t> v = i.GetVoxel();
5491  if (v.CWiseAllGE(m_1) && v.CWiseAllLE(m_2))
5492  {
5493  bool newSurface = false;
5494  switch (m_axis)
5495  {
5496  case SplitAxis::X_AXIS_NEGATIVE:
5497  if (v.GetX() == splitLoc)
5498  {
5499  newSurface = true;
5500  }
5501  break;
5502  case SplitAxis::X_AXIS_POSITIVE:
5503  if (v.GetX() == m_1.GetX())
5504  {
5505  newSurface = true;
5506  }
5507  break;
5508  case SplitAxis::Y_AXIS_NEGATIVE:
5509  if (v.GetY() == splitLoc)
5510  {
5511  newSurface = true;
5512  }
5513  break;
5514  case SplitAxis::Y_AXIS_POSITIVE:
5515  if (v.GetY() == m_1.GetY())
5516  {
5517  newSurface = true;
5518  }
5519  break;
5520  case SplitAxis::Z_AXIS_NEGATIVE:
5521  if (v.GetZ() == splitLoc)
5522  {
5523  newSurface = true;
5524  }
5525  break;
5526  case SplitAxis::Z_AXIS_POSITIVE:
5527  if (v.GetZ() == m_1.GetZ())
5528  {
5529  newSurface = true;
5530  }
5531  break;
5532  }
5533  // If his interior voxels lie directly on the split plane then
5534  // these become new surface voxels for our patch
5535  if (newSurface)
5536  {
5537  m_newSurfaceVoxels.push_back(i);
5538  }
5539  else
5540  {
5541  m_interiorVoxels.push_back(i);
5542  }
5543  }
5544  }
5545  // Next we copy all of the surface voxels which intersect our region
5546  for (auto& i : parent.m_surfaceVoxels)
5547  {
5548  VHACD::Vector3<uint32_t> v = i.GetVoxel();
5549  if (v.CWiseAllGE(m_1) && v.CWiseAllLE(m_2))
5550  {
5551  m_surfaceVoxels.push_back(i);
5552  }
5553  }
5554  // Our parent's new surface voxels become our new surface voxels so long as they intersect our region
5555  for (auto& i : parent.m_newSurfaceVoxels)
5556  {
5557  VHACD::Vector3<uint32_t> v = i.GetVoxel();
5558  if (v.CWiseAllGE(m_1) && v.CWiseAllLE(m_2))
5559  {
5560  m_newSurfaceVoxels.push_back(i);
5561  }
5562  }
5563 
5564  // Recompute the min-max bounding box which would be different after the split occurs
5565  m_1 = VHACD::Vector3<uint32_t>(0x7FFFFFFF);
5566  m_2 = VHACD::Vector3<uint32_t>(0);
5567  for (auto& i : m_surfaceVoxels)
5568  {
5569  MinMaxVoxelRegion(i);
5570  }
5571  for (auto& i : m_newSurfaceVoxels)
5572  {
5573  MinMaxVoxelRegion(i);
5574  }
5575  for (auto& i : m_interiorVoxels)
5576  {
5577  MinMaxVoxelRegion(i);
5578  }
5579 
5580  BuildVoxelMesh();
5581  BuildRaycastMesh(); // build a raycast mesh of the voxel mesh
5582  ComputeConvexHull();
5583 }
5584 
5585 VoxelHull::VoxelHull(Volume& voxels, const IVHACD::Parameters& params, VHACDCallbacks* callbacks)
5586  : m_voxels(&voxels)
5587  , m_voxelScale(m_voxels->GetScale())
5588  , m_voxelScaleHalf(m_voxelScale * double(0.5))
5589  , m_voxelBounds(m_voxels->GetBounds())
5590  , m_voxelAdjust(m_voxelBounds.GetMin() - m_voxelScaleHalf)
5591  , m_index(++m_voxelHullCount)
5592  // Here we get a copy of all voxels which lie on the surface mesh
5593  , m_surfaceVoxels(m_voxels->GetSurfaceVoxels())
5594  // Now we get a copy of all voxels which are considered part of the 'interior' of the source mesh
5595  , m_interiorVoxels(m_voxels->GetInteriorVoxels())
5596  , m_2(m_voxels->GetDimensions() - 1)
5597  , m_params(params)
5598  , m_callbacks(callbacks)
5599 {
5600  BuildVoxelMesh();
5601  BuildRaycastMesh(); // build a raycast mesh of the voxel mesh
5602  ComputeConvexHull();
5603 }
5604 
5605 void VoxelHull::MinMaxVoxelRegion(const Voxel& v)
5606 {
5607  VHACD::Vector3<uint32_t> x = v.GetVoxel();
5608  m_1 = m_1.CWiseMin(x);
5609  m_2 = m_2.CWiseMax(x);
5610 }
5611 
5612 void VoxelHull::BuildRaycastMesh()
5613 {
5614  // Create a raycast mesh representation of the voxelized surface mesh
5615  if (!m_indices.empty())
5616  {
5617  m_AABBTree = AABBTree(m_vertices, m_indices);
5618  }
5619 }
5620 
5621 void VoxelHull::ComputeConvexHull()
5622 {
5623  if (!m_vertices.empty())
5624  {
5625  // we compute the convex hull as follows...
5626  VHACD::QuickHull qh;
5627  uint32_t tcount = qh.ComputeConvexHull(m_vertices, uint32_t(m_vertices.size()));
5628  if (tcount)
5629  {
5630  m_convexHull = std::unique_ptr<IVHACD::ConvexHull>(new IVHACD::ConvexHull);
5631 
5632  m_convexHull->m_points = qh.GetVertices();
5633  m_convexHull->m_triangles = qh.GetIndices();
5634 
5635  VHACD::ComputeCentroid(m_convexHull->m_points, m_convexHull->m_triangles, m_convexHull->m_center);
5636  m_convexHull->m_volume = VHACD::ComputeMeshVolume(m_convexHull->m_points, m_convexHull->m_triangles);
5637  }
5638  }
5639  if (m_convexHull)
5640  {
5641  m_hullVolume = m_convexHull->m_volume;
5642  }
5643  // This is the volume of a single voxel
5644  double singleVoxelVolume = m_voxelScale * m_voxelScale * m_voxelScale;
5645  size_t voxelCount = m_interiorVoxels.size() + m_newSurfaceVoxels.size() + m_surfaceVoxels.size();
5646  m_voxelVolume = singleVoxelVolume * double(voxelCount);
5647  double diff = fabs(m_hullVolume - m_voxelVolume);
5648  m_volumeError = (diff * 100) / m_voxelVolume;
5649 }
5650 
5651 bool VoxelHull::IsComplete()
5652 {
5653  bool ret = false;
5654  if (m_convexHull == nullptr)
5655  {
5656  ret = true;
5657  }
5658  else if (m_volumeError < m_params.m_minimumVolumePercentErrorAllowed)
5659  {
5660  ret = true;
5661  }
5662  else if (m_depth > m_params.m_maxRecursionDepth)
5663  {
5664  ret = true;
5665  }
5666  else
5667  {
5668  // We compute the voxel width on all 3 axes and see if they are below the min threshold size
5669  VHACD::Vector3<uint32_t> d = m_2 - m_1;
5670  if (d.GetX() <= m_params.m_minEdgeLength && d.GetY() <= m_params.m_minEdgeLength &&
5671  d.GetZ() <= m_params.m_minEdgeLength)
5672  {
5673  ret = true;
5674  }
5675  }
5676  return ret;
5677 }
5678 
5679 VHACD::Vect3 VoxelHull::GetPoint(const int32_t x,
5680  const int32_t y,
5681  const int32_t z,
5682  const double scale,
5683  const VHACD::Vect3& bmin) const
5684 {
5685  return VHACD::Vect3(x * scale + bmin.GetX(), y * scale + bmin.GetY(), z * scale + bmin.GetZ());
5686 }
5687 
5688 uint32_t VoxelHull::GetVertexIndex(const VHACD::Vector3<uint32_t>& p)
5689 {
5690  uint32_t ret = 0;
5691  uint32_t address = (p.GetX() << 20) | (p.GetY() << 10) | p.GetZ();
5692  auto found = m_voxelIndexMap.find(address);
5693  if (found != m_voxelIndexMap.end())
5694  {
5695  ret = found->second;
5696  }
5697  else
5698  {
5699  VHACD::Vect3 vertex = GetPoint(p.GetX(), p.GetY(), p.GetZ(), m_voxelScale, m_voxelAdjust);
5700  ret = uint32_t(m_voxelIndexMap.size());
5701  m_voxelIndexMap[address] = ret;
5702  m_vertices.emplace_back(vertex);
5703  }
5704  return ret;
5705 }
5706 
5707 void VoxelHull::BuildVoxelMesh()
5708 {
5709  // When we build the triangle mesh we do *not* need the interior voxels, only the ones
5710  // which lie upon the logical surface of the mesh.
5711  // Each time we perform a plane split, voxels which are along the splitting plane become
5712  // 'new surface voxels'.
5713 
5714  for (auto& i : m_surfaceVoxels)
5715  {
5716  AddVoxelBox(i);
5717  }
5718  for (auto& i : m_newSurfaceVoxels)
5719  {
5720  AddVoxelBox(i);
5721  }
5722 }
5723 
5724 void VoxelHull::AddVoxelBox(const Voxel& v)
5725 {
5726  // The voxel position of the upper left corner of the box
5727  VHACD::Vector3<uint32_t> bmin(v.GetX(), v.GetY(), v.GetZ());
5728  // The voxel position of the lower right corner of the box
5729  VHACD::Vector3<uint32_t> bmax(bmin.GetX() + 1, bmin.GetY() + 1, bmin.GetZ() + 1);
5730 
5731  // Build the set of 8 voxel positions representing
5732  // the coordinates of the box
5733  std::array<VHACD::Vector3<uint32_t>, 8> box{ { { bmin.GetX(), bmin.GetY(), bmin.GetZ() },
5734  { bmax.GetX(), bmin.GetY(), bmin.GetZ() },
5735  { bmax.GetX(), bmax.GetY(), bmin.GetZ() },
5736  { bmin.GetX(), bmax.GetY(), bmin.GetZ() },
5737  { bmin.GetX(), bmin.GetY(), bmax.GetZ() },
5738  { bmax.GetX(), bmin.GetY(), bmax.GetZ() },
5739  { bmax.GetX(), bmax.GetY(), bmax.GetZ() },
5740  { bmin.GetX(), bmax.GetY(), bmax.GetZ() } } };
5741 
5742  // Now add the 12 triangles comprising the 3d box
5743  AddTri(box, 2, 1, 0);
5744  AddTri(box, 3, 2, 0);
5745 
5746  AddTri(box, 7, 2, 3);
5747  AddTri(box, 7, 6, 2);
5748 
5749  AddTri(box, 5, 1, 2);
5750  AddTri(box, 5, 2, 6);
5751 
5752  AddTri(box, 5, 4, 1);
5753  AddTri(box, 4, 0, 1);
5754 
5755  AddTri(box, 4, 6, 7);
5756  AddTri(box, 4, 5, 6);
5757 
5758  AddTri(box, 4, 7, 0);
5759  AddTri(box, 7, 3, 0);
5760 }
5761 
5762 void VoxelHull::AddTri(const std::array<VHACD::Vector3<uint32_t>, 8>& box, uint32_t i1, uint32_t i2, uint32_t i3)
5763 {
5764  AddTriangle(box[i1], box[i2], box[i3]);
5765 }
5766 
5767 void VoxelHull::AddTriangle(const VHACD::Vector3<uint32_t>& p1,
5768  const VHACD::Vector3<uint32_t>& p2,
5769  const VHACD::Vector3<uint32_t>& p3)
5770 {
5771  uint32_t i1 = GetVertexIndex(p1);
5772  uint32_t i2 = GetVertexIndex(p2);
5773  uint32_t i3 = GetVertexIndex(p3);
5774 
5775  m_indices.emplace_back(i1, i2, i3);
5776 }
5777 
5778 SplitAxis VoxelHull::ComputeSplitPlane(uint32_t& location)
5779 {
5780  SplitAxis ret = SplitAxis::X_AXIS_NEGATIVE;
5781 
5782  VHACD::Vector3<uint32_t> d = m_2 - m_1;
5783 
5784  if (d.GetX() >= d.GetY() && d.GetX() >= d.GetZ())
5785  {
5786  ret = SplitAxis::X_AXIS_NEGATIVE;
5787  location = (m_2.GetX() + 1 + m_1.GetX()) / 2;
5788  uint32_t edgeLoc;
5789  if (m_params.m_findBestPlane && FindConcavityX(edgeLoc))
5790  {
5791  location = edgeLoc;
5792  }
5793  }
5794  else if (d.GetY() >= d.GetX() && d.GetY() >= d.GetZ())
5795  {
5796  ret = SplitAxis::Y_AXIS_NEGATIVE;
5797  location = (m_2.GetY() + 1 + m_1.GetY()) / 2;
5798  uint32_t edgeLoc;
5799  if (m_params.m_findBestPlane && FindConcavityY(edgeLoc))
5800  {
5801  location = edgeLoc;
5802  }
5803  }
5804  else
5805  {
5806  ret = SplitAxis::Z_AXIS_NEGATIVE;
5807  location = (m_2.GetZ() + 1 + m_1.GetZ()) / 2;
5808  uint32_t edgeLoc;
5809  if (m_params.m_findBestPlane && FindConcavityZ(edgeLoc))
5810  {
5811  location = edgeLoc;
5812  }
5813  }
5814 
5815  return ret;
5816 }
5817 
5818 VHACD::Vect3 VoxelHull::GetPosition(const VHACD::Vector3<int32_t>& ip) const
5819 {
5820  return GetPoint(ip.GetX(), ip.GetY(), ip.GetZ(), m_voxelScale, m_voxelAdjust);
5821 }
5822 
5823 double VoxelHull::Raycast(const VHACD::Vector3<int32_t>& p1, const VHACD::Vector3<int32_t>& p2) const
5824 {
5825  double ret;
5826  VHACD::Vect3 from = GetPosition(p1);
5827  VHACD::Vect3 to = GetPosition(p2);
5828 
5829  double outT;
5830  double faceSign;
5831  VHACD::Vect3 hitLocation;
5832  if (m_AABBTree.TraceRay(from, to, outT, faceSign, hitLocation))
5833  {
5834  ret = (from - hitLocation).GetNorm();
5835  }
5836  else
5837  {
5838  ret = 0; // if it doesn't hit anything, just assign it to zero.
5839  }
5840 
5841  return ret;
5842 }
5843 
5844 bool VoxelHull::FindConcavity(uint32_t idx, uint32_t& splitLoc)
5845 {
5846  bool ret = false;
5847 
5848  int32_t d = (m_2[idx] - m_1[idx]) + 1; // The length of the getX axis in voxel space
5849 
5850  uint32_t idx1;
5851  uint32_t idx2;
5852  uint32_t idx3;
5853  switch (idx)
5854  {
5855  case 0: // X
5856  idx1 = 0;
5857  idx2 = 1;
5858  idx3 = 2;
5859  break;
5860  case 1: // Y
5861  idx1 = 1;
5862  idx2 = 0;
5863  idx3 = 2;
5864  break;
5865  case 2:
5866  idx1 = 2;
5867  idx2 = 1;
5868  idx3 = 0;
5869  break;
5870  default:
5871  /*
5872  * To silence uninitialized variable warnings
5873  */
5874  idx1 = 0;
5875  idx2 = 0;
5876  idx3 = 0;
5877  assert(0 && "findConcavity::idx must be 0, 1, or 2");
5878  break;
5879  }
5880 
5881  // We will compute the edge error on the XY plane and the XZ plane
5882  // searching for the greatest location of concavity
5883  std::vector<double> edgeError1 = std::vector<double>(d);
5884  std::vector<double> edgeError2 = std::vector<double>(d);
5885 
5886  // Counter of number of voxel samples on the XY plane we have accumulated
5887  uint32_t index1 = 0;
5888 
5889  // Compute Edge Error on the XY plane
5890  for (uint32_t i0 = m_1[idx1]; i0 <= m_2[idx1]; i0++)
5891  {
5892  double errorTotal = 0;
5893  // We now perform a raycast from the sides inward on the XY plane to
5894  // determine the total error (distance of the surface from the sides)
5895  // along this getX position.
5896  for (uint32_t i1 = m_1[idx2]; i1 <= m_2[idx2]; i1++)
5897  {
5900  switch (idx)
5901  {
5902  case 0:
5903  {
5904  p1 = VHACD::Vector3<int32_t>(i0, i1, m_1.GetZ() - 2);
5905  p2 = VHACD::Vector3<int32_t>(i0, i1, m_2.GetZ() + 2);
5906  break;
5907  }
5908  case 1:
5909  {
5910  p1 = VHACD::Vector3<int32_t>(i1, i0, m_1.GetZ() - 2);
5911  p2 = VHACD::Vector3<int32_t>(i1, i0, m_2.GetZ() + 2);
5912  break;
5913  }
5914  case 2:
5915  {
5916  p1 = VHACD::Vector3<int32_t>(m_1.GetX() - 2, i1, i0);
5917  p2 = VHACD::Vector3<int32_t>(m_2.GetX() + 2, i1, i0);
5918  break;
5919  }
5920  }
5921 
5922  double e1 = Raycast(p1, p2);
5923  double e2 = Raycast(p2, p1);
5924 
5925  errorTotal = errorTotal + e1 + e2;
5926  }
5927  // The total amount of edge error along this voxel location
5928  edgeError1[index1] = errorTotal;
5929  index1++;
5930  }
5931 
5932  // Compute edge error along the XZ plane
5933  uint32_t index2 = 0;
5934 
5935  for (uint32_t i0 = m_1[idx1]; i0 <= m_2[idx1]; i0++)
5936  {
5937  double errorTotal = 0;
5938 
5939  for (uint32_t i1 = m_1[idx3]; i1 <= m_2[idx3]; i1++)
5940  {
5943  switch (idx)
5944  {
5945  case 0:
5946  {
5947  p1 = VHACD::Vector3<int32_t>(i0, m_1.GetY() - 2, i1);
5948  p2 = VHACD::Vector3<int32_t>(i0, m_2.GetY() + 2, i1);
5949  break;
5950  }
5951  case 1:
5952  {
5953  p1 = VHACD::Vector3<int32_t>(m_1.GetX() - 2, i0, i1);
5954  p2 = VHACD::Vector3<int32_t>(m_2.GetX() + 2, i0, i1);
5955  break;
5956  }
5957  case 2:
5958  {
5959  p1 = VHACD::Vector3<int32_t>(i1, m_1.GetY() - 2, i0);
5960  p2 = VHACD::Vector3<int32_t>(i1, m_2.GetY() + 2, i0);
5961  break;
5962  }
5963  }
5964 
5965  double e1 = Raycast(p1, p2); // raycast from one side to the interior
5966  double e2 = Raycast(p2, p1); // raycast from the other side to the interior
5967 
5968  errorTotal = errorTotal + e1 + e2;
5969  }
5970  edgeError2[index2] = errorTotal;
5971  index2++;
5972  }
5973 
5974  // we now compute the first derivative to find the greatest spot of concavity on the XY plane
5975  double maxDiff = 0;
5976  uint32_t maxC = 0;
5977  for (uint32_t x = 1; x < index1; x++)
5978  {
5979  if (edgeError1[x] > 0 && edgeError1[x - 1] > 0)
5980  {
5981  double diff = abs(edgeError1[x] - edgeError1[x - 1]);
5982  if (diff > maxDiff)
5983  {
5984  maxDiff = diff;
5985  maxC = x - 1;
5986  }
5987  }
5988  }
5989 
5990  // Now see if there is a greater concavity on the XZ plane
5991  for (uint32_t x = 1; x < index2; x++)
5992  {
5993  if (edgeError2[x] > 0 && edgeError2[x - 1] > 0)
5994  {
5995  double diff = abs(edgeError2[x] - edgeError2[x - 1]);
5996  if (diff > maxDiff)
5997  {
5998  maxDiff = diff;
5999  maxC = x - 1;
6000  }
6001  }
6002  }
6003 
6004  splitLoc = maxC + m_1[idx1];
6005 
6006  // we do not allow an edge split if it is too close to the ends
6007  if (splitLoc > (m_1[idx1] + 4) && splitLoc < (m_2[idx1] - 4))
6008  {
6009  ret = true;
6010  }
6011 
6012  return ret;
6013 }
6014 
6015 // Finding the greatest area of concavity..
6016 bool VoxelHull::FindConcavityX(uint32_t& splitLoc) { return FindConcavity(0, splitLoc); }
6017 
6018 // Finding the greatest area of concavity..
6019 bool VoxelHull::FindConcavityY(uint32_t& splitLoc) { return FindConcavity(1, splitLoc); }
6020 
6021 // Finding the greatest area of concavity..
6022 bool VoxelHull::FindConcavityZ(uint32_t& splitLoc) { return FindConcavity(2, splitLoc); }
6023 
6024 void VoxelHull::PerformPlaneSplit()
6025 {
6026  if (IsComplete())
6027  {
6028  }
6029  else
6030  {
6031  uint32_t splitLoc;
6032  SplitAxis axis = ComputeSplitPlane(splitLoc);
6033  switch (axis)
6034  {
6035  case SplitAxis::X_AXIS_NEGATIVE:
6036  case SplitAxis::X_AXIS_POSITIVE:
6037  // Split on the getX axis at this split location
6038  m_hullA = std::unique_ptr<VoxelHull>(new VoxelHull(*this, SplitAxis::X_AXIS_NEGATIVE, splitLoc));
6039  m_hullB = std::unique_ptr<VoxelHull>(new VoxelHull(*this, SplitAxis::X_AXIS_POSITIVE, splitLoc));
6040  break;
6041  case SplitAxis::Y_AXIS_NEGATIVE:
6042  case SplitAxis::Y_AXIS_POSITIVE:
6043  // Split on the 1 axis at this split location
6044  m_hullA = std::unique_ptr<VoxelHull>(new VoxelHull(*this, SplitAxis::Y_AXIS_NEGATIVE, splitLoc));
6045  m_hullB = std::unique_ptr<VoxelHull>(new VoxelHull(*this, SplitAxis::Y_AXIS_POSITIVE, splitLoc));
6046  break;
6047  case SplitAxis::Z_AXIS_NEGATIVE:
6048  case SplitAxis::Z_AXIS_POSITIVE:
6049  // Split on the getZ axis at this split location
6050  m_hullA = std::unique_ptr<VoxelHull>(new VoxelHull(*this, SplitAxis::Z_AXIS_NEGATIVE, splitLoc));
6051  m_hullB = std::unique_ptr<VoxelHull>(new VoxelHull(*this, SplitAxis::Z_AXIS_POSITIVE, splitLoc));
6052  break;
6053  }
6054  }
6055 }
6056 
6057 void VoxelHull::SaveVoxelMesh(const SimpleMesh& inputMesh, bool saveVoxelMesh, bool saveSourceMesh)
6058 {
6059  char scratch[512];
6060  snprintf(scratch, sizeof(scratch), "voxel-mesh-%03d.obj", m_index);
6061  FILE* fph = fopen(scratch, "wb");
6062  if (fph)
6063  {
6064  uint32_t baseIndex = 1;
6065  if (saveVoxelMesh)
6066  {
6067  WriteOBJ(fph, m_vertices, m_indices, baseIndex);
6068  baseIndex += uint32_t(m_vertices.size());
6069  }
6070  if (saveSourceMesh)
6071  {
6072  WriteOBJ(fph, inputMesh.m_vertices, inputMesh.m_indices, baseIndex);
6073  }
6074  fclose(fph);
6075  }
6076 }
6077 
6078 void VoxelHull::SaveOBJ(const char* fname, const VoxelHull* h)
6079 {
6080  FILE* fph = fopen(fname, "wb");
6081  if (fph)
6082  {
6083  uint32_t baseIndex = 1;
6084  WriteOBJ(fph, m_vertices, m_indices, baseIndex);
6085 
6086  baseIndex += uint32_t(m_vertices.size());
6087 
6088  WriteOBJ(fph, h->m_vertices, h->m_indices, baseIndex);
6089  fclose(fph);
6090  }
6091 }
6092 
6093 void VoxelHull::SaveOBJ(const char* fname)
6094 {
6095  FILE* fph = fopen(fname, "wb");
6096  if (fph)
6097  {
6098  printf("Saving '%s' with %d vertices and %d triangles\n",
6099  fname,
6100  uint32_t(m_vertices.size()),
6101  uint32_t(m_indices.size()));
6102  WriteOBJ(fph, m_vertices, m_indices, 1);
6103  fclose(fph);
6104  }
6105 }
6106 
6107 void VoxelHull::WriteOBJ(FILE* fph,
6108  const std::vector<VHACD::Vertex>& vertices,
6109  const std::vector<VHACD::Triangle>& indices,
6110  uint32_t baseIndex)
6111 {
6112  if (!fph)
6113  {
6114  return;
6115  }
6116 
6117  for (size_t i = 0; i < vertices.size(); ++i)
6118  {
6119  const VHACD::Vertex& v = vertices[i];
6120  fprintf(fph, "v %0.9f %0.9f %0.9f\n", v.mX, v.mY, v.mZ);
6121  }
6122 
6123  for (size_t i = 0; i < indices.size(); ++i)
6124  {
6125  const VHACD::Triangle& t = indices[i];
6126  fprintf(fph, "f %d %d %d\n", t.mI0 + baseIndex, t.mI1 + baseIndex, t.mI2 + baseIndex);
6127  }
6128 }
6129 
6130 class VHACDImpl;
6131 
6132 // This class represents a single task to compute the volume error
6133 // of two convex hulls combined
6134 class CostTask
6135 {
6136 public:
6137  VHACDImpl* m_this{ nullptr };
6138  IVHACD::ConvexHull* m_hullA{ nullptr };
6139  IVHACD::ConvexHull* m_hullB{ nullptr };
6140  double m_concavity{ 0 }; // concavity of the two combined
6141  std::future<void> m_future;
6142 };
6143 
6144 class HullPair
6145 {
6146 public:
6147  HullPair() = default;
6148  HullPair(uint32_t hullA, uint32_t hullB, double concavity);
6149 
6150  bool operator<(const HullPair& h) const;
6151 
6152  uint32_t m_hullA{ 0 };
6153  uint32_t m_hullB{ 0 };
6154  double m_concavity{ 0 };
6155 };
6156 
6157 HullPair::HullPair(uint32_t hullA, uint32_t hullB, double concavity)
6158  : m_hullA(hullA), m_hullB(hullB), m_concavity(concavity)
6159 {
6160 }
6161 
6162 bool HullPair::operator<(const HullPair& h) const { return m_concavity > h.m_concavity ? true : false; }
6163 
6164 // void jobCallback(void* userPtr);
6165 
6166 class VHACDImpl : public IVHACD, public VHACDCallbacks
6167 {
6168  // Don't consider more than 100,000 convex hulls.
6169  static constexpr uint32_t MaxConvexHullFragments{ 100000 };
6170 
6171 public:
6172  VHACDImpl() = default;
6173 
6174  /*
6175  * Overrides VHACD::IVHACD
6176  */
6177  ~VHACDImpl() override { Clean(); }
6178 
6179  void Cancel() override final;
6180 
6181  bool Compute(const float* const points,
6182  const uint32_t countPoints,
6183  const uint32_t* const triangles,
6184  const uint32_t countTriangles,
6185  const Parameters& params) override final;
6186 
6187  bool Compute(const double* const points,
6188  const uint32_t countPoints,
6189  const uint32_t* const triangles,
6190  const uint32_t countTriangles,
6191  const Parameters& params) override final;
6192 
6193  uint32_t GetNConvexHulls() const override final;
6194 
6195  bool GetConvexHull(const uint32_t index, ConvexHull& ch) const override final;
6196 
6197  void Clean() override final; // release internally allocated memory
6198 
6199  void Release() override final;
6200 
6201  // Will compute the center of mass of the convex hull decomposition results and return it
6202  // in 'centerOfMass'. Returns false if the center of mass could not be computed.
6203  bool ComputeCenterOfMass(double centerOfMass[3]) const override final;
6204 
6205  // In synchronous mode (non-multi-threaded) the state is always 'ready'
6206  // In asynchronous mode, this returns true if the background thread is not still actively computing
6207  // a new solution. In an asynchronous config the 'IsReady' call will report any update or log
6208  // messages in the caller's current thread.
6209  bool IsReady(void) const override final;
6210 
6221  uint32_t findNearestConvexHull(const double pos[3], double& distanceToHull) override final;
6222 
6223  // private:
6224  bool Compute(const std::vector<VHACD::Vertex>& points,
6225  const std::vector<VHACD::Triangle>& triangles,
6226  const Parameters& params);
6227 
6228  // Take the source position, normalize it, and then convert it into an index position
6229  uint32_t GetIndex(VHACD::VertexIndex& vi, const VHACD::Vertex& p);
6230 
6231  // This copies the input mesh while scaling the input positions
6232  // to fit into a normalized unit cube. It also re-indexes all of the
6233  // vertex positions in case they weren't clean coming in.
6234  void CopyInputMesh(const std::vector<VHACD::Vertex>& points, const std::vector<VHACD::Triangle>& triangles);
6235 
6236  void ScaleOutputConvexHull(ConvexHull& ch);
6237 
6238  void AddCostToPriorityQueue(CostTask& task);
6239 
6240  void ReleaseConvexHull(ConvexHull* ch);
6241 
6242  void PerformConvexDecomposition();
6243 
6244  double ComputeConvexHullVolume(const ConvexHull& sm);
6245 
6246  double ComputeVolume4(const VHACD::Vect3& a, const VHACD::Vect3& b, const VHACD::Vect3& c, const VHACD::Vect3& d);
6247 
6248  double ComputeConcavity(double volumeSeparate, double volumeCombined, double volumeMesh);
6249 
6250  // See if we can compute the cost without having to actually merge convex hulls.
6251  // If the axis aligned bounding boxes (slightly inflated) of the two convex hulls
6252  // do not intersect, then we don't need to actually compute the merged convex hull
6253  // volume.
6254  bool DoFastCost(CostTask& mt);
6255 
6256  void PerformMergeCostTask(CostTask& mt);
6257 
6258  ConvexHull* ComputeReducedConvexHull(const ConvexHull& ch, uint32_t maxVerts, bool projectHullVertices);
6259 
6260  // Take the points in convex hull A and the points in convex hull B and generate
6261  // a new convex hull on the combined set of points.
6262  // Once completed, we create a SimpleMesh instance to hold the triangle mesh
6263  // and we compute an inflated AABB for it.
6264  ConvexHull* ComputeCombinedConvexHull(const ConvexHull& sm1, const ConvexHull& sm2);
6265 
6266  ConvexHull* GetHull(uint32_t index);
6267 
6268  bool RemoveHull(uint32_t index);
6269 
6270  ConvexHull* CopyConvexHull(const ConvexHull& source);
6271 
6272  const char* GetStageName(Stages stage) const;
6273 
6274  /*
6275  * Overrides VHACD::VHACDCallbacks
6276  */
6277  void ProgressUpdate(Stages stage, double stageProgress, const char* operation) override final;
6278 
6279  bool IsCanceled() const override final;
6280 
6281  std::atomic<bool> m_canceled{ false };
6282  Parameters m_params; // Convex decomposition parameters
6283 
6284  std::vector<IVHACD::ConvexHull*> m_convexHulls; // Finalized convex hulls
6285  std::vector<std::unique_ptr<VoxelHull>> m_voxelHulls; // completed voxel hulls
6286  std::vector<std::unique_ptr<VoxelHull>> m_pendingHulls;
6287 
6288  std::vector<std::unique_ptr<AABBTree>> m_trees;
6289  VHACD::AABBTree m_AABBTree;
6290  VHACD::Volume m_voxelize;
6291  VHACD::Vect3 m_center;
6292  double m_scale{ double(1.0) };
6293  double m_recipScale{ double(1.0) };
6294  SimpleMesh m_inputMesh; // re-indexed and normalized input mesh
6295  std::vector<VHACD::Vertex> m_vertices;
6296  std::vector<VHACD::Triangle> m_indices;
6297 
6298  double m_overallHullVolume{ double(0.0) };
6299  double m_voxelScale{ double(0.0) };
6300  double m_voxelHalfScale{ double(0.0) };
6301  VHACD::Vect3 m_voxelBmin;
6302  VHACD::Vect3 m_voxelBmax;
6303  uint32_t m_meshId{ 0 };
6304  std::priority_queue<HullPair> m_hullPairQueue;
6305 #if !VHACD_DISABLE_THREADING
6306  std::unique_ptr<ThreadPool> m_threadPool{ nullptr };
6307 #endif
6308  std::unordered_map<uint32_t, IVHACD::ConvexHull*> m_hulls;
6309 
6310  double m_overallProgress{ double(0.0) };
6311  double m_stageProgress{ double(0.0) };
6312  double m_operationProgress{ double(0.0) };
6313 };
6314 
6315 void VHACDImpl::Cancel() { m_canceled = true; }
6316 
6317 bool VHACDImpl::Compute(const float* const points,
6318  const uint32_t countPoints,
6319  const uint32_t* const triangles,
6320  const uint32_t countTriangles,
6321  const Parameters& params)
6322 {
6323  std::vector<VHACD::Vertex> v;
6324  v.reserve(countPoints);
6325  for (uint32_t i = 0; i < countPoints; ++i)
6326  {
6327  v.emplace_back(points[i * 3 + 0], points[i * 3 + 1], points[i * 3 + 2]);
6328  }
6329 
6330  std::vector<VHACD::Triangle> t;
6331  t.reserve(countTriangles);
6332  for (uint32_t i = 0; i < countTriangles; ++i)
6333  {
6334  t.emplace_back(triangles[i * 3 + 0], triangles[i * 3 + 1], triangles[i * 3 + 2]);
6335  }
6336 
6337  return Compute(v, t, params);
6338 }
6339 
6340 bool VHACDImpl::Compute(const double* const points,
6341  const uint32_t countPoints,
6342  const uint32_t* const triangles,
6343  const uint32_t countTriangles,
6344  const Parameters& params)
6345 {
6346  std::vector<VHACD::Vertex> v;
6347  v.reserve(countPoints);
6348  for (uint32_t i = 0; i < countPoints; ++i)
6349  {
6350  v.emplace_back(points[i * 3 + 0], points[i * 3 + 1], points[i * 3 + 2]);
6351  }
6352 
6353  std::vector<VHACD::Triangle> t;
6354  t.reserve(countTriangles);
6355  for (uint32_t i = 0; i < countTriangles; ++i)
6356  {
6357  t.emplace_back(triangles[i * 3 + 0], triangles[i * 3 + 1], triangles[i * 3 + 2]);
6358  }
6359 
6360  return Compute(v, t, params);
6361 }
6362 
6363 uint32_t VHACDImpl::GetNConvexHulls() const { return uint32_t(m_convexHulls.size()); }
6364 
6365 bool VHACDImpl::GetConvexHull(const uint32_t index, ConvexHull& ch) const
6366 {
6367  bool ret = false;
6368 
6369  if (index < uint32_t(m_convexHulls.size()))
6370  {
6371  ch = *m_convexHulls[index];
6372  ret = true;
6373  }
6374 
6375  return ret;
6376 }
6377 
6378 void VHACDImpl::Clean()
6379 {
6380 #if !VHACD_DISABLE_THREADING
6381  m_threadPool = nullptr;
6382 #endif
6383 
6384  m_trees.clear();
6385 
6386  for (auto& ch : m_convexHulls)
6387  {
6388  ReleaseConvexHull(ch);
6389  }
6390  m_convexHulls.clear();
6391 
6392  for (auto& ch : m_hulls)
6393  {
6394  ReleaseConvexHull(ch.second);
6395  }
6396  m_hulls.clear();
6397 
6398  m_voxelHulls.clear();
6399 
6400  m_pendingHulls.clear();
6401 
6402  m_vertices.clear();
6403  m_indices.clear();
6404 }
6405 
6406 void VHACDImpl::Release() { delete this; }
6407 
6408 bool VHACDImpl::ComputeCenterOfMass(double centerOfMass[3]) const
6409 {
6410  bool ret = false;
6411 
6412  return ret;
6413 }
6414 
6415 bool VHACDImpl::IsReady() const { return true; }
6416 
6417 uint32_t VHACDImpl::findNearestConvexHull(const double pos[3], double& distanceToHull)
6418 {
6419  uint32_t ret = 0; // The default return code is zero
6420 
6421  uint32_t hullCount = GetNConvexHulls();
6422  distanceToHull = 0;
6423  // First, make sure that we have valid and completed results
6424  if (hullCount)
6425  {
6426  // See if we already have AABB trees created for each convex hull
6427  if (m_trees.empty())
6428  {
6429  // For each convex hull, we generate an AABB tree for fast closest point queries
6430  for (uint32_t i = 0; i < hullCount; i++)
6431  {
6433  GetConvexHull(i, ch);
6434  // Pass the triangle mesh to create an AABB tree instance based on it.
6435  m_trees.emplace_back(new AABBTree(ch.m_points, ch.m_triangles));
6436  }
6437  }
6438  // We now compute the closest point to each convex hull and save the nearest one
6439  double closest = 1e99;
6440  for (uint32_t i = 0; i < hullCount; i++)
6441  {
6442  std::unique_ptr<AABBTree>& t = m_trees[i];
6443  if (t)
6444  {
6445  VHACD::Vect3 closestPoint;
6446  VHACD::Vect3 position(pos[0], pos[1], pos[2]);
6447  if (t->GetClosestPointWithinDistance(position, 1e99, closestPoint))
6448  {
6449  VHACD::Vect3 d = position - closestPoint;
6450  double distanceSquared = d.GetNormSquared();
6451  if (distanceSquared < closest)
6452  {
6453  closest = distanceSquared;
6454  ret = i;
6455  }
6456  }
6457  }
6458  }
6459  distanceToHull = sqrt(closest); // compute the distance to the nearest convex hull
6460  }
6461 
6462  return ret;
6463 }
6464 
6465 bool VHACDImpl::Compute(const std::vector<VHACD::Vertex>& points,
6466  const std::vector<VHACD::Triangle>& triangles,
6467  const Parameters& params)
6468 {
6469  bool ret = false;
6470 
6471  m_params = params;
6472  m_canceled = false;
6473 
6474  Clean(); // release any previous results
6475 #if !VHACD_DISABLE_THREADING
6476  if (m_params.m_asyncACD)
6477  {
6478  m_threadPool = std::unique_ptr<ThreadPool>(new ThreadPool(8));
6479  }
6480 #endif
6481  CopyInputMesh(points, triangles);
6482  if (!m_canceled)
6483  {
6484  // We now recursively perform convex decomposition until complete
6485  PerformConvexDecomposition();
6486  }
6487 
6488  if (m_canceled)
6489  {
6490  Clean();
6491  ret = false;
6492  if (m_params.m_logger)
6493  {
6494  m_params.m_logger->Log("VHACD operation canceled before it was complete.");
6495  }
6496  }
6497  else
6498  {
6499  ret = true;
6500  }
6501 #if !VHACD_DISABLE_THREADING
6502  m_threadPool = nullptr;
6503 #endif
6504  return ret;
6505 }
6506 
6507 uint32_t VHACDImpl::GetIndex(VHACD::VertexIndex& vi, const VHACD::Vertex& p)
6508 {
6509  VHACD::Vect3 pos = (VHACD::Vect3(p) - m_center) * m_recipScale;
6510  bool newPos;
6511  uint32_t ret = vi.GetIndex(pos, newPos);
6512  return ret;
6513 }
6514 
6515 void VHACDImpl::CopyInputMesh(const std::vector<VHACD::Vertex>& points, const std::vector<VHACD::Triangle>& triangles)
6516 {
6517  m_vertices.clear();
6518  m_indices.clear();
6519  m_indices.reserve(triangles.size());
6520 
6521  // First we must find the bounding box of this input vertices and normalize them into a unit-cube
6522  VHACD::Vect3 bmin(FLT_MAX);
6523  VHACD::Vect3 bmax(-FLT_MAX);
6524  ProgressUpdate(Stages::COMPUTE_BOUNDS_OF_INPUT_MESH, 0, "ComputingBounds");
6525  for (uint32_t i = 0; i < points.size(); i++)
6526  {
6527  const VHACD::Vertex& p = points[i];
6528 
6529  bmin = bmin.CWiseMin(p);
6530  bmax = bmax.CWiseMax(p);
6531  }
6532  ProgressUpdate(Stages::COMPUTE_BOUNDS_OF_INPUT_MESH, 100, "ComputingBounds");
6533 
6534  m_center = (bmax + bmin) * double(0.5);
6535 
6536  VHACD::Vect3 scale = bmax - bmin;
6537  m_scale = scale.MaxCoeff();
6538 
6539  m_recipScale = m_scale > double(0.0) ? double(1.0) / m_scale : double(0.0);
6540 
6541  {
6542  VHACD::VertexIndex vi = VHACD::VertexIndex(double(0.001), false);
6543 
6544  uint32_t dcount = 0;
6545 
6546  for (uint32_t i = 0; i < triangles.size() && !m_canceled; ++i)
6547  {
6548  const VHACD::Triangle& t = triangles[i];
6549  const VHACD::Vertex& p1 = points[t.mI0];
6550  const VHACD::Vertex& p2 = points[t.mI1];
6551  const VHACD::Vertex& p3 = points[t.mI2];
6552 
6553  uint32_t i1 = GetIndex(vi, p1);
6554  uint32_t i2 = GetIndex(vi, p2);
6555  uint32_t i3 = GetIndex(vi, p3);
6556 
6557  if (i1 == i2 || i1 == i3 || i2 == i3)
6558  {
6559  dcount++;
6560  }
6561  else
6562  {
6563  m_indices.emplace_back(i1, i2, i3);
6564  }
6565  }
6566 
6567  if (dcount)
6568  {
6569  if (m_params.m_logger)
6570  {
6571  char scratch[512];
6572  snprintf(scratch, sizeof(scratch), "Skipped %d degenerate triangles", dcount);
6573  m_params.m_logger->Log(scratch);
6574  }
6575  }
6576 
6577  m_vertices = vi.TakeVertices();
6578  }
6579 
6580  // Create the raycast mesh
6581  if (!m_canceled)
6582  {
6583  ProgressUpdate(Stages::CREATE_RAYCAST_MESH, 0, "Building RaycastMesh");
6584  m_AABBTree = VHACD::AABBTree(m_vertices, m_indices);
6585  ProgressUpdate(Stages::CREATE_RAYCAST_MESH, 100, "RaycastMesh completed");
6586  }
6587  if (!m_canceled)
6588  {
6589  ProgressUpdate(Stages::VOXELIZING_INPUT_MESH, 0, "Voxelizing Input Mesh");
6590  m_voxelize = VHACD::Volume();
6591  m_voxelize.Voxelize(m_vertices, m_indices, m_params.m_resolution, m_params.m_fillMode, m_AABBTree);
6592  m_voxelScale = m_voxelize.GetScale();
6593  m_voxelHalfScale = m_voxelScale * double(0.5);
6594  m_voxelBmin = m_voxelize.GetBounds().GetMin();
6595  m_voxelBmax = m_voxelize.GetBounds().GetMax();
6596  ProgressUpdate(Stages::VOXELIZING_INPUT_MESH, 100, "Voxelization complete");
6597  }
6598 
6599  m_inputMesh.m_vertices = m_vertices;
6600  m_inputMesh.m_indices = m_indices;
6601  if (!m_canceled)
6602  {
6603  ProgressUpdate(Stages::BUILD_INITIAL_CONVEX_HULL, 0, "Build initial ConvexHull");
6604  std::unique_ptr<VoxelHull> vh = std::unique_ptr<VoxelHull>(new VoxelHull(m_voxelize, m_params, this));
6605  if (vh->m_convexHull)
6606  {
6607  m_overallHullVolume = vh->m_convexHull->m_volume;
6608  }
6609  m_pendingHulls.push_back(std::move(vh));
6610  ProgressUpdate(Stages::BUILD_INITIAL_CONVEX_HULL, 100, "Initial ConvexHull complete");
6611  }
6612 }
6613 
6614 void VHACDImpl::ScaleOutputConvexHull(ConvexHull& ch)
6615 {
6616  for (uint32_t i = 0; i < ch.m_points.size(); i++)
6617  {
6618  VHACD::Vect3 p = ch.m_points[i];
6619  p = (p * m_scale) + m_center;
6620  ch.m_points[i] = p;
6621  }
6622  ch.m_volume = ComputeConvexHullVolume(ch); // get the combined volume
6623  VHACD::BoundsAABB b(ch.m_points);
6624  ch.mBmin = b.GetMin();
6625  ch.mBmax = b.GetMax();
6626  ComputeCentroid(ch.m_points, ch.m_triangles, ch.m_center);
6627 }
6628 
6629 void VHACDImpl::AddCostToPriorityQueue(CostTask& task)
6630 {
6631  HullPair hp(task.m_hullA->m_meshId, task.m_hullB->m_meshId, task.m_concavity);
6632  m_hullPairQueue.push(hp);
6633 }
6634 
6635 void VHACDImpl::ReleaseConvexHull(ConvexHull* ch)
6636 {
6637  if (ch)
6638  {
6639  delete ch;
6640  }
6641 }
6642 
6643 void jobCallback(std::unique_ptr<VoxelHull>& userPtr) { userPtr->PerformPlaneSplit(); }
6644 
6645 void computeMergeCostTask(CostTask& ptr) { ptr.m_this->PerformMergeCostTask(ptr); }
6646 
6647 void VHACDImpl::PerformConvexDecomposition()
6648 {
6649  {
6650  ScopedTime st("Convex Decomposition", m_params.m_logger);
6651  double maxHulls = pow(2, m_params.m_maxRecursionDepth);
6652  // We recursively split convex hulls until we can
6653  // no longer recurse further.
6654  Timer t;
6655 
6656  while (!m_pendingHulls.empty() && !m_canceled)
6657  {
6658  size_t count = m_pendingHulls.size() + m_voxelHulls.size();
6659  double e = t.PeekElapsedSeconds();
6660  if (e >= double(0.1))
6661  {
6662  t.Reset();
6663  double stageProgress = (double(count) * double(100.0)) / maxHulls;
6664  ProgressUpdate(
6665  Stages::PERFORMING_DECOMPOSITION, stageProgress, "Performing recursive decomposition of convex hulls");
6666  }
6667  // First we make a copy of the hulls we are processing
6668  std::vector<std::unique_ptr<VoxelHull>> oldList = std::move(m_pendingHulls);
6669  // For each hull we want to split, we either
6670  // immediately perform the plane split or we post it as
6671  // a job to be performed in a background thread
6672  std::vector<std::future<void>> futures(oldList.size());
6673  uint32_t futureCount = 0;
6674  for (auto& i : oldList)
6675  {
6676  if (i->IsComplete() || count > MaxConvexHullFragments)
6677  {
6678  }
6679  else
6680  {
6681 #if !VHACD_DISABLE_THREADING
6682  if (m_threadPool)
6683  {
6684  futures[futureCount] = m_threadPool->enqueue([&i] { jobCallback(i); });
6685  futureCount++;
6686  }
6687  else
6688 #endif
6689  {
6690  i->PerformPlaneSplit();
6691  }
6692  }
6693  }
6694  // Wait for any outstanding jobs to complete in the background threads
6695  if (futureCount)
6696  {
6697  for (uint32_t i = 0; i < futureCount; i++)
6698  {
6699  futures[i].get();
6700  }
6701  }
6702  // Now, we rebuild the pending convex hulls list by
6703  // adding the two children to the output list if
6704  // we need to recurse them further
6705  for (auto& vh : oldList)
6706  {
6707  if (vh->IsComplete() || count > MaxConvexHullFragments)
6708  {
6709  if (vh->m_convexHull)
6710  {
6711  m_voxelHulls.push_back(std::move(vh));
6712  }
6713  }
6714  else
6715  {
6716  if (vh->m_hullA)
6717  {
6718  m_pendingHulls.push_back(std::move(vh->m_hullA));
6719  }
6720  if (vh->m_hullB)
6721  {
6722  m_pendingHulls.push_back(std::move(vh->m_hullB));
6723  }
6724  }
6725  }
6726  }
6727  }
6728 
6729  if (!m_canceled)
6730  {
6731  // Give each convex hull a unique guid
6732  m_meshId = 0;
6733  m_hulls.clear();
6734 
6735  // Build the convex hull id map
6736  std::vector<ConvexHull*> hulls;
6737 
6738  ProgressUpdate(Stages::INITIALIZING_CONVEX_HULLS_FOR_MERGING, 0, "Initializing ConvexHulls");
6739  for (auto& vh : m_voxelHulls)
6740  {
6741  if (m_canceled)
6742  {
6743  break;
6744  }
6745  ConvexHull* ch = CopyConvexHull(*vh->m_convexHull);
6746  m_meshId++;
6747  ch->m_meshId = m_meshId;
6748  m_hulls[m_meshId] = ch;
6749  // Compute the volume of the convex hull
6750  ch->m_volume = ComputeConvexHullVolume(*ch);
6751  // Compute the AABB of the convex hull
6752  VHACD::BoundsAABB b = VHACD::BoundsAABB(ch->m_points).Inflate(double(0.1));
6753  ch->mBmin = b.GetMin();
6754  ch->mBmax = b.GetMax();
6755 
6756  ComputeCentroid(ch->m_points, ch->m_triangles, ch->m_center);
6757 
6758  hulls.push_back(ch);
6759  }
6760  ProgressUpdate(Stages::INITIALIZING_CONVEX_HULLS_FOR_MERGING, 100, "ConvexHull initialization complete");
6761 
6762  m_voxelHulls.clear();
6763 
6764  // here we merge convex hulls as needed until the match the
6765  // desired maximum hull count.
6766  size_t hullCount = hulls.size();
6767 
6768  if (hullCount > m_params.m_maxConvexHulls && !m_canceled)
6769  {
6770  size_t costMatrixSize = ((hullCount * hullCount) - hullCount) >> 1;
6771  std::vector<CostTask> tasks;
6772  tasks.reserve(costMatrixSize);
6773 
6774  ScopedTime st("Computing the Cost Matrix", m_params.m_logger);
6775  // First thing we need to do is compute the cost matrix
6776  // This is computed as the volume error of any two convex hulls
6777  // combined
6778  ProgressUpdate(Stages::COMPUTING_COST_MATRIX, 0, "Computing Hull Merge Cost Matrix");
6779  for (size_t i = 1; i < hullCount && !m_canceled; i++)
6780  {
6781  ConvexHull* chA = hulls[i];
6782 
6783  for (size_t j = 0; j < i && !m_canceled; j++)
6784  {
6785  ConvexHull* chB = hulls[j];
6786 
6787  CostTask t;
6788  t.m_hullA = chA;
6789  t.m_hullB = chB;
6790  t.m_this = this;
6791 
6792  if (DoFastCost(t))
6793  {
6794  }
6795  else
6796  {
6797  tasks.push_back(std::move(t));
6798  CostTask* task = &tasks.back();
6799 #if !VHACD_DISABLE_THREADING
6800  if (m_threadPool)
6801  {
6802  task->m_future = m_threadPool->enqueue([task] { computeMergeCostTask(*task); });
6803  }
6804 #endif
6805  }
6806  }
6807  }
6808 
6809  if (!m_canceled)
6810  {
6811 #if !VHACD_DISABLE_THREADING
6812  if (m_threadPool)
6813  {
6814  for (CostTask& task : tasks)
6815  {
6816  task.m_future.get();
6817  }
6818 
6819  for (CostTask& task : tasks)
6820  {
6821  AddCostToPriorityQueue(task);
6822  }
6823  }
6824  else
6825 #endif
6826  {
6827  for (CostTask& task : tasks)
6828  {
6829  PerformMergeCostTask(task);
6830  AddCostToPriorityQueue(task);
6831  }
6832  }
6833  ProgressUpdate(Stages::COMPUTING_COST_MATRIX, 100, "Finished cost matrix");
6834  }
6835 
6836  if (!m_canceled)
6837  {
6838  ScopedTime stMerging("Merging Convex Hulls", m_params.m_logger);
6839  Timer t;
6840  // Now that we know the cost to merge each hull, we can begin merging them.
6841  bool cancel = false;
6842 
6843  uint32_t maxMergeCount = uint32_t(m_hulls.size()) - m_params.m_maxConvexHulls;
6844  uint32_t startCount = uint32_t(m_hulls.size());
6845 
6846  while (!cancel && m_hulls.size() > m_params.m_maxConvexHulls && !m_hullPairQueue.empty() && !m_canceled)
6847  {
6848  double e = t.PeekElapsedSeconds();
6849  if (e >= double(0.1))
6850  {
6851  t.Reset();
6852  uint32_t hullsProcessed = startCount - uint32_t(m_hulls.size());
6853  double stageProgress = double(hullsProcessed * 100) / double(maxMergeCount);
6854  ProgressUpdate(Stages::MERGING_CONVEX_HULLS, stageProgress, "Merging Convex Hulls");
6855  }
6856 
6857  HullPair hp = m_hullPairQueue.top();
6858  m_hullPairQueue.pop();
6859 
6860  // It is entirely possible that the hull pair queue can
6861  // have references to convex hulls that are no longer valid
6862  // because they were previously merged. So we check for this
6863  // and if either hull referenced in this pair no longer
6864  // exists, then we skip it.
6865 
6866  // Look up this pair of hulls by ID
6867  ConvexHull* ch1 = GetHull(hp.m_hullA);
6868  ConvexHull* ch2 = GetHull(hp.m_hullB);
6869 
6870  // If both hulls are still valid, then we merge them, delete the old
6871  // two hulls and recompute the cost matrix for the new combined hull
6872  // we have created
6873  if (ch1 && ch2)
6874  {
6875  // This is the convex hull which results from combining the
6876  // vertices in the two source hulls
6877  ConvexHull* combinedHull = ComputeCombinedConvexHull(*ch1, *ch2);
6878  // The two old convex hulls are going to get removed
6879  RemoveHull(hp.m_hullA);
6880  RemoveHull(hp.m_hullB);
6881 
6882  m_meshId++;
6883  combinedHull->m_meshId = m_meshId;
6884  tasks.clear();
6885  tasks.reserve(m_hulls.size());
6886 
6887  // Compute the cost between this new merged hull
6888  // and all existing convex hulls and then
6889  // add that to the priority queue
6890  for (auto& i : m_hulls)
6891  {
6892  if (m_canceled)
6893  {
6894  break;
6895  }
6896  ConvexHull* secondHull = i.second;
6897  CostTask ct;
6898  ct.m_hullA = combinedHull;
6899  ct.m_hullB = secondHull;
6900  ct.m_this = this;
6901  if (DoFastCost(ct))
6902  {
6903  }
6904  else
6905  {
6906  tasks.push_back(std::move(ct));
6907  }
6908  }
6909  m_hulls[combinedHull->m_meshId] = combinedHull;
6910  // See how many merge cost tasks were posted
6911  // If there are 8 or more and we are running asynchronously, then do them that way.
6912 #if !VHACD_DISABLE_THREADING
6913  if (m_threadPool && tasks.size() >= 2)
6914  {
6915  for (CostTask& task : tasks)
6916  {
6917  task.m_future = m_threadPool->enqueue([&task] { computeMergeCostTask(task); });
6918  }
6919 
6920  for (CostTask& task : tasks)
6921  {
6922  task.m_future.get();
6923  }
6924  }
6925  else
6926 #endif
6927  {
6928  for (CostTask& task : tasks)
6929  {
6930  PerformMergeCostTask(task);
6931  }
6932  }
6933 
6934  for (CostTask& task : tasks)
6935  {
6936  AddCostToPriorityQueue(task);
6937  }
6938  }
6939  }
6940  // Ok...once we are done, we copy the results!
6941  m_meshId -= 0;
6942  ProgressUpdate(Stages::FINALIZING_RESULTS, 0, "Finalizing results");
6943  for (auto& i : m_hulls)
6944  {
6945  if (m_canceled)
6946  {
6947  break;
6948  }
6949  ConvexHull* ch = i.second;
6950  // We now must reduce the convex hull
6951  if (ch->m_points.size() > m_params.m_maxNumVerticesPerCH || m_params.m_shrinkWrap)
6952  {
6953  ConvexHull* reduce = ComputeReducedConvexHull(*ch, m_params.m_maxNumVerticesPerCH, m_params.m_shrinkWrap);
6954  ReleaseConvexHull(ch);
6955  ch = reduce;
6956  }
6957  ScaleOutputConvexHull(*ch);
6958  ch->m_meshId = m_meshId;
6959  m_meshId++;
6960  m_convexHulls.push_back(ch);
6961  }
6962  m_hulls.clear(); // since the hulls were moved into the output list, we don't need to delete them from this
6963  // container
6964  ProgressUpdate(Stages::FINALIZING_RESULTS, 100, "Finalized results complete");
6965  }
6966  }
6967  else
6968  {
6969  ProgressUpdate(Stages::FINALIZING_RESULTS, 0, "Finalizing results");
6970  m_meshId = 0;
6971  for (auto& ch : hulls)
6972  {
6973  // We now must reduce the convex hull
6974  if (ch->m_points.size() > m_params.m_maxNumVerticesPerCH || m_params.m_shrinkWrap)
6975  {
6976  ConvexHull* reduce = ComputeReducedConvexHull(*ch, m_params.m_maxNumVerticesPerCH, m_params.m_shrinkWrap);
6977  ReleaseConvexHull(ch);
6978  ch = reduce;
6979  }
6980  ScaleOutputConvexHull(*ch);
6981  ch->m_meshId = m_meshId;
6982  m_meshId++;
6983  m_convexHulls.push_back(ch);
6984  }
6985  m_hulls.clear();
6986  ProgressUpdate(Stages::FINALIZING_RESULTS, 100, "Finalized results");
6987  }
6988  }
6989 }
6990 
6991 double VHACDImpl::ComputeConvexHullVolume(const ConvexHull& sm)
6992 {
6993  double totalVolume = 0;
6994  VHACD::Vect3 bary(0, 0, 0);
6995  for (uint32_t i = 0; i < sm.m_points.size(); i++)
6996  {
6997  VHACD::Vect3 p(sm.m_points[i]);
6998  bary += p;
6999  }
7000  bary /= double(sm.m_points.size());
7001 
7002  for (uint32_t i = 0; i < sm.m_triangles.size(); i++)
7003  {
7004  uint32_t i1 = sm.m_triangles[i].mI0;
7005  uint32_t i2 = sm.m_triangles[i].mI1;
7006  uint32_t i3 = sm.m_triangles[i].mI2;
7007 
7008  VHACD::Vect3 ver0(sm.m_points[i1]);
7009  VHACD::Vect3 ver1(sm.m_points[i2]);
7010  VHACD::Vect3 ver2(sm.m_points[i3]);
7011 
7012  totalVolume += ComputeVolume4(ver0, ver1, ver2, bary);
7013  }
7014  totalVolume = totalVolume / double(6.0);
7015  return totalVolume;
7016 }
7017 
7018 double
7019 VHACDImpl::ComputeVolume4(const VHACD::Vect3& a, const VHACD::Vect3& b, const VHACD::Vect3& c, const VHACD::Vect3& d)
7020 {
7021  VHACD::Vect3 ad = a - d;
7022  VHACD::Vect3 bd = b - d;
7023  VHACD::Vect3 cd = c - d;
7024  VHACD::Vect3 bcd = bd.Cross(cd);
7025  double dot = ad.Dot(bcd);
7026  return dot;
7027 }
7028 
7029 double VHACDImpl::ComputeConcavity(double volumeSeparate, double volumeCombined, double volumeMesh)
7030 {
7031  return fabs(volumeSeparate - volumeCombined) / volumeMesh;
7032 }
7033 
7034 bool VHACDImpl::DoFastCost(CostTask& mt)
7035 {
7036  bool ret = false;
7037 
7038  ConvexHull* ch1 = mt.m_hullA;
7039  ConvexHull* ch2 = mt.m_hullB;
7040 
7041  VHACD::BoundsAABB ch1b(ch1->mBmin, ch1->mBmax);
7042  VHACD::BoundsAABB ch2b(ch2->mBmin, ch2->mBmax);
7043  if (!ch1b.Intersects(ch2b))
7044  {
7045  VHACD::BoundsAABB b = ch1b.Union(ch2b);
7046 
7047  double combinedVolume = b.Volume();
7048  double concavity = ComputeConcavity(ch1->m_volume + ch2->m_volume, combinedVolume, m_overallHullVolume);
7049  HullPair hp(ch1->m_meshId, ch2->m_meshId, concavity);
7050  m_hullPairQueue.push(hp);
7051  ret = true;
7052  }
7053  return ret;
7054 }
7055 
7056 void VHACDImpl::PerformMergeCostTask(CostTask& mt)
7057 {
7058  ConvexHull* ch1 = mt.m_hullA;
7059  ConvexHull* ch2 = mt.m_hullB;
7060 
7061  double volume1 = ch1->m_volume;
7062  double volume2 = ch2->m_volume;
7063 
7064  ConvexHull* combined = ComputeCombinedConvexHull(*ch1,
7065  *ch2); // Build the combined convex hull
7066  double combinedVolume = ComputeConvexHullVolume(*combined); // get the combined volume
7067  mt.m_concavity = ComputeConcavity(volume1 + volume2, combinedVolume, m_overallHullVolume);
7068  ReleaseConvexHull(combined);
7069 }
7070 
7071 IVHACD::ConvexHull* VHACDImpl::ComputeReducedConvexHull(const ConvexHull& ch,
7072  uint32_t maxVerts,
7073  bool projectHullVertices)
7074 {
7075  SimpleMesh sourceConvexHull;
7076 
7077  sourceConvexHull.m_vertices = ch.m_points;
7078  sourceConvexHull.m_indices = ch.m_triangles;
7079 
7080  ShrinkWrap(sourceConvexHull, m_AABBTree, maxVerts, m_voxelScale * 4, projectHullVertices);
7081 
7082  ConvexHull* ret = new ConvexHull;
7083 
7084  ret->m_points = sourceConvexHull.m_vertices;
7085  ret->m_triangles = sourceConvexHull.m_indices;
7086 
7087  VHACD::BoundsAABB b = VHACD::BoundsAABB(ret->m_points).Inflate(double(0.1));
7088  ret->mBmin = b.GetMin();
7089  ret->mBmax = b.GetMax();
7090  ComputeCentroid(ret->m_points, ret->m_triangles, ret->m_center);
7091 
7092  ret->m_volume = ComputeConvexHullVolume(*ret);
7093 
7094  // Return the convex hull
7095  return ret;
7096 }
7097 
7098 IVHACD::ConvexHull* VHACDImpl::ComputeCombinedConvexHull(const ConvexHull& sm1, const ConvexHull& sm2)
7099 {
7100  uint32_t vcount = uint32_t(sm1.m_points.size() + sm2.m_points.size()); // Total vertices from both hulls
7101  std::vector<VHACD::Vertex> vertices(vcount);
7102  auto it = std::copy(sm1.m_points.begin(), sm1.m_points.end(), vertices.begin());
7103  std::copy(sm2.m_points.begin(), sm2.m_points.end(), it);
7104 
7105  VHACD::QuickHull qh;
7106  qh.ComputeConvexHull(vertices, vcount);
7107 
7108  ConvexHull* ret = new ConvexHull;
7109  ret->m_points = qh.GetVertices();
7110  ret->m_triangles = qh.GetIndices();
7111 
7112  ret->m_volume = ComputeConvexHullVolume(*ret);
7113 
7114  VHACD::BoundsAABB b = VHACD::BoundsAABB(qh.GetVertices()).Inflate(double(0.1));
7115  ret->mBmin = b.GetMin();
7116  ret->mBmax = b.GetMax();
7117  ComputeCentroid(ret->m_points, ret->m_triangles, ret->m_center);
7118 
7119  // Return the convex hull
7120  return ret;
7121 }
7122 
7123 IVHACD::ConvexHull* VHACDImpl::GetHull(uint32_t index)
7124 {
7125  ConvexHull* ret = nullptr;
7126 
7127  auto found = m_hulls.find(index);
7128  if (found != m_hulls.end())
7129  {
7130  ret = found->second;
7131  }
7132 
7133  return ret;
7134 }
7135 
7136 bool VHACDImpl::RemoveHull(uint32_t index)
7137 {
7138  bool ret = false;
7139  auto found = m_hulls.find(index);
7140  if (found != m_hulls.end())
7141  {
7142  ret = true;
7143  ReleaseConvexHull(found->second);
7144  m_hulls.erase(found);
7145  }
7146  return ret;
7147 }
7148 
7149 IVHACD::ConvexHull* VHACDImpl::CopyConvexHull(const ConvexHull& source)
7150 {
7151  ConvexHull* ch = new ConvexHull;
7152  *ch = source;
7153 
7154  return ch;
7155 }
7156 
7157 const char* VHACDImpl::GetStageName(Stages stage) const
7158 {
7159  const char* ret = "unknown";
7160  switch (stage)
7161  {
7162  case Stages::COMPUTE_BOUNDS_OF_INPUT_MESH:
7163  ret = "COMPUTE_BOUNDS_OF_INPUT_MESH";
7164  break;
7165  case Stages::REINDEXING_INPUT_MESH:
7166  ret = "REINDEXING_INPUT_MESH";
7167  break;
7168  case Stages::CREATE_RAYCAST_MESH:
7169  ret = "CREATE_RAYCAST_MESH";
7170  break;
7171  case Stages::VOXELIZING_INPUT_MESH:
7172  ret = "VOXELIZING_INPUT_MESH";
7173  break;
7174  case Stages::BUILD_INITIAL_CONVEX_HULL:
7175  ret = "BUILD_INITIAL_CONVEX_HULL";
7176  break;
7177  case Stages::PERFORMING_DECOMPOSITION:
7178  ret = "PERFORMING_DECOMPOSITION";
7179  break;
7180  case Stages::INITIALIZING_CONVEX_HULLS_FOR_MERGING:
7181  ret = "INITIALIZING_CONVEX_HULLS_FOR_MERGING";
7182  break;
7183  case Stages::COMPUTING_COST_MATRIX:
7184  ret = "COMPUTING_COST_MATRIX";
7185  break;
7186  case Stages::MERGING_CONVEX_HULLS:
7187  ret = "MERGING_CONVEX_HULLS";
7188  break;
7189  case Stages::FINALIZING_RESULTS:
7190  ret = "FINALIZING_RESULTS";
7191  break;
7192  case Stages::NUM_STAGES:
7193  // Should be unreachable, here to silence enumeration value not handled in switch warnings
7194  // GCC/Clang's -Wswitch
7195  break;
7196  }
7197  return ret;
7198 }
7199 
7200 void VHACDImpl::ProgressUpdate(Stages stage, double stageProgress, const char* operation)
7201 {
7202  if (m_params.m_callback)
7203  {
7204  double overallProgress = (double(stage) * 100) / double(Stages::NUM_STAGES);
7205  const char* s = GetStageName(stage);
7206  m_params.m_callback->Update(overallProgress, stageProgress, s, operation);
7207  }
7208 }
7209 
7210 bool VHACDImpl::IsCanceled() const { return m_canceled; }
7211 
7212 IVHACD* CreateVHACD(void)
7213 {
7214  VHACDImpl* ret = new VHACDImpl;
7215  return static_cast<IVHACD*>(ret);
7216 }
7217 
7218 IVHACD* CreateVHACD(void);
7219 
7220 #if !VHACD_DISABLE_THREADING
7221 
7222 class LogMessage
7223 {
7224 public:
7225  double m_overallProgress{ double(-1.0) };
7226  double m_stageProgress{ double(-1.0) };
7227  std::string m_stage;
7228  std::string m_operation;
7229 };
7230 
7231 class VHACDAsyncImpl : public VHACD::IVHACD,
7235 {
7236 public:
7237  VHACDAsyncImpl() = default;
7238 
7239  ~VHACDAsyncImpl() override;
7240 
7241  void Cancel() override final;
7242 
7243  bool Compute(const float* const points,
7244  const uint32_t countPoints,
7245  const uint32_t* const triangles,
7246  const uint32_t countTriangles,
7247  const Parameters& params) override final;
7248 
7249  bool Compute(const double* const points,
7250  const uint32_t countPoints,
7251  const uint32_t* const triangles,
7252  const uint32_t countTriangles,
7253  const Parameters& params) override final;
7254 
7255  bool GetConvexHull(const uint32_t index, VHACD::IVHACD::ConvexHull& ch) const override final;
7256 
7257  uint32_t GetNConvexHulls() const override final;
7258 
7259  void Clean() override final; // release internally allocated memory
7260 
7261  void Release() override final; // release IVHACD
7262 
7263  // Will compute the center of mass of the convex hull decomposition results and return it
7264  // in 'centerOfMass'. Returns false if the center of mass could not be computed.
7265  bool ComputeCenterOfMass(double centerOfMass[3]) const override;
7266 
7267  bool IsReady() const override final;
7268 
7279  uint32_t findNearestConvexHull(const double pos[3], double& distanceToHull) override final;
7280 
7281  void Update(const double overallProgress,
7282  const double stageProgress,
7283  const char* const stage,
7284  const char* operation) override final;
7285 
7286  void Log(const char* const msg) override final;
7287 
7288  void* StartTask(std::function<void()> func) override;
7289 
7290  void JoinTask(void* Task) override;
7291 
7292  bool Compute(const Parameters params);
7293 
7294  bool ComputeNow(const std::vector<VHACD::Vertex>& points,
7295  const std::vector<VHACD::Triangle>& triangles,
7296  const Parameters& _desc);
7297 
7298  // As a convenience for the calling application we only send it update and log messages from it's own main
7299  // thread. This reduces the complexity burden on the caller by making sure it only has to deal with log
7300  // messages in it's main application thread.
7301  void ProcessPendingMessages() const;
7302 
7303 private:
7304  VHACD::VHACDImpl m_VHACD;
7305  std::vector<VHACD::Vertex> m_vertices;
7306  std::vector<VHACD::Triangle> m_indices;
7307  VHACD::IVHACD::IUserCallback* m_callback{ nullptr };
7308  VHACD::IVHACD::IUserLogger* m_logger{ nullptr };
7309  VHACD::IVHACD::IUserTaskRunner* m_taskRunner{ nullptr };
7310  void* m_task{ nullptr };
7311  std::atomic<bool> m_running{ false };
7312  std::atomic<bool> m_cancel{ false };
7313 
7314  // Thread safe caching mechanism for messages and update status.
7315  // This is so that caller always gets messages in his own thread
7316  // Member variables are marked as 'mutable' since the message dispatch function
7317  // is called from const query methods.
7318  mutable std::mutex m_messageMutex;
7319  mutable std::vector<LogMessage> m_messages;
7320  mutable std::atomic<bool> m_haveMessages{ false };
7321 };
7322 
7323 VHACDAsyncImpl::~VHACDAsyncImpl() { Cancel(); }
7324 
7325 void VHACDAsyncImpl::Cancel()
7326 {
7327  m_cancel = true;
7328  m_VHACD.Cancel();
7329 
7330  if (m_task)
7331  {
7332  m_taskRunner->JoinTask(m_task); // Wait for the thread to fully exit before we delete the instance
7333  m_task = nullptr;
7334  }
7335  m_cancel = false; // clear the cancel semaphore
7336 }
7337 
7338 bool VHACDAsyncImpl::Compute(const float* const points,
7339  const uint32_t countPoints,
7340  const uint32_t* const triangles,
7341  const uint32_t countTriangles,
7342  const Parameters& params)
7343 {
7344  m_vertices.reserve(countPoints);
7345  for (uint32_t i = 0; i < countPoints; ++i)
7346  {
7347  m_vertices.emplace_back(points[i * 3 + 0], points[i * 3 + 1], points[i * 3 + 2]);
7348  }
7349 
7350  m_indices.reserve(countTriangles);
7351  for (uint32_t i = 0; i < countTriangles; ++i)
7352  {
7353  m_indices.emplace_back(triangles[i * 3 + 0], triangles[i * 3 + 1], triangles[i * 3 + 2]);
7354  }
7355 
7356  return Compute(params);
7357 }
7358 
7359 bool VHACDAsyncImpl::Compute(const double* const points,
7360  const uint32_t countPoints,
7361  const uint32_t* const triangles,
7362  const uint32_t countTriangles,
7363  const Parameters& params)
7364 {
7365  // We need to copy the input vertices and triangles into our own buffers so we can operate
7366  // on them safely from the background thread.
7367  // Can't be local variables due to being asynchronous
7368  m_vertices.reserve(countPoints);
7369  for (uint32_t i = 0; i < countPoints; ++i)
7370  {
7371  m_vertices.emplace_back(points[i * 3 + 0], points[i * 3 + 1], points[i * 3 + 2]);
7372  }
7373 
7374  m_indices.reserve(countTriangles);
7375  for (uint32_t i = 0; i < countTriangles; ++i)
7376  {
7377  m_indices.emplace_back(triangles[i * 3 + 0], triangles[i * 3 + 1], triangles[i * 3 + 2]);
7378  }
7379 
7380  return Compute(params);
7381 }
7382 
7383 bool VHACDAsyncImpl::GetConvexHull(const uint32_t index, VHACD::IVHACD::ConvexHull& ch) const
7384 {
7385  return m_VHACD.GetConvexHull(index, ch);
7386 }
7387 
7388 uint32_t VHACDAsyncImpl::GetNConvexHulls() const
7389 {
7390  ProcessPendingMessages();
7391  return m_VHACD.GetNConvexHulls();
7392 }
7393 
7394 void VHACDAsyncImpl::Clean()
7395 {
7396  Cancel();
7397  m_VHACD.Clean();
7398 }
7399 
7400 void VHACDAsyncImpl::Release() { delete this; }
7401 
7402 bool VHACDAsyncImpl::ComputeCenterOfMass(double centerOfMass[3]) const
7403 {
7404  bool ret = false;
7405 
7406  centerOfMass[0] = 0;
7407  centerOfMass[1] = 0;
7408  centerOfMass[2] = 0;
7409 
7410  if (IsReady())
7411  {
7412  ret = m_VHACD.ComputeCenterOfMass(centerOfMass);
7413  }
7414  return ret;
7415 }
7416 
7417 bool VHACDAsyncImpl::IsReady() const
7418 {
7419  ProcessPendingMessages();
7420  return !m_running;
7421 }
7422 
7423 uint32_t VHACDAsyncImpl::findNearestConvexHull(const double pos[3], double& distanceToHull)
7424 {
7425  uint32_t ret = 0; // The default return code is zero
7426 
7427  distanceToHull = 0;
7428  // First, make sure that we have valid and completed results
7429  if (IsReady())
7430  {
7431  ret = m_VHACD.findNearestConvexHull(pos, distanceToHull);
7432  }
7433 
7434  return ret;
7435 }
7436 
7437 void VHACDAsyncImpl::Update(const double overallProgress,
7438  const double stageProgress,
7439  const char* const stage,
7440  const char* operation)
7441 {
7442  m_messageMutex.lock();
7443  LogMessage m;
7444  m.m_operation = std::string(operation);
7445  m.m_overallProgress = overallProgress;
7446  m.m_stageProgress = stageProgress;
7447  m.m_stage = std::string(stage);
7448  m_messages.push_back(m);
7449  m_haveMessages = true;
7450  m_messageMutex.unlock();
7451 }
7452 
7453 void VHACDAsyncImpl::Log(const char* const msg)
7454 {
7455  m_messageMutex.lock();
7456  LogMessage m;
7457  m.m_operation = std::string(msg);
7458  m_haveMessages = true;
7459  m_messages.push_back(m);
7460  m_messageMutex.unlock();
7461 }
7462 
7463 void* VHACDAsyncImpl::StartTask(std::function<void()> func) { return new std::thread(func); }
7464 
7465 void VHACDAsyncImpl::JoinTask(void* Task)
7466 {
7467  std::thread* t = static_cast<std::thread*>(Task);
7468  t->join();
7469  delete t;
7470 }
7471 
7472 bool VHACDAsyncImpl::Compute(Parameters params)
7473 {
7474  Cancel(); // if we previously had a solution running; cancel it.
7475 
7476  m_taskRunner = params.m_taskRunner ? params.m_taskRunner : this;
7477  params.m_taskRunner = m_taskRunner;
7478 
7479  m_running = true;
7480  m_task = m_taskRunner->StartTask([this, params]() {
7481  ComputeNow(m_vertices, m_indices, params);
7482  // If we have a user provided callback and the user did *not* call 'cancel' we notify him that the
7483  // task is completed. However..if the user selected 'cancel' we do not send a completed notification event.
7484  if (params.m_callback && !m_cancel)
7485  {
7486  params.m_callback->NotifyVHACDComplete();
7487  }
7488  m_running = false;
7489  });
7490  return true;
7491 }
7492 
7493 bool VHACDAsyncImpl::ComputeNow(const std::vector<VHACD::Vertex>& points,
7494  const std::vector<VHACD::Triangle>& triangles,
7495  const Parameters& _desc)
7496 {
7497  uint32_t ret = 0;
7498 
7499  Parameters desc;
7500  m_callback = _desc.m_callback;
7501  m_logger = _desc.m_logger;
7502 
7503  desc = _desc;
7504  // Set our intercepting callback interfaces if non-null
7505  desc.m_callback = _desc.m_callback ? this : nullptr;
7506  desc.m_logger = _desc.m_logger ? this : nullptr;
7507 
7508  // If not task runner provided, then use the default one
7509  if (desc.m_taskRunner == nullptr)
7510  {
7511  desc.m_taskRunner = this;
7512  }
7513 
7514  bool ok = m_VHACD.Compute(points, triangles, desc);
7515  if (ok)
7516  {
7517  ret = m_VHACD.GetNConvexHulls();
7518  }
7519 
7520  return ret ? true : false;
7521 }
7522 
7523 void VHACDAsyncImpl::ProcessPendingMessages() const
7524 {
7525  if (m_cancel)
7526  {
7527  return;
7528  }
7529  if (m_haveMessages)
7530  {
7531  m_messageMutex.lock();
7532  for (auto& i : m_messages)
7533  {
7534  if (i.m_overallProgress == -1)
7535  {
7536  if (m_logger)
7537  {
7538  m_logger->Log(i.m_operation.c_str());
7539  }
7540  }
7541  else if (m_callback)
7542  {
7543  m_callback->Update(i.m_overallProgress, i.m_stageProgress, i.m_stage.c_str(), i.m_operation.c_str());
7544  }
7545  }
7546  m_messages.clear();
7547  m_haveMessages = false;
7548  m_messageMutex.unlock();
7549  }
7550 }
7551 
7552 IVHACD* CreateVHACD_ASYNC()
7553 {
7554  VHACDAsyncImpl* m = new VHACDAsyncImpl;
7555  return static_cast<IVHACD*>(m);
7556 }
7557 #endif
7558 
7559 } // namespace VHACD
7560 
7561 #ifdef _MSC_VER
7562 #pragma warning(pop)
7563 #endif // _MSC_VER
7564 
7565 #ifdef __GNUC__
7566 #pragma GCC diagnostic pop
7567 #endif // __GNUC__
7568 
7569 #endif // ENABLE_VHACD_IMPLEMENTATION
7570 
7571 #endif // VHACD_H
7572 TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
VHACD::IVHACD::IUserCallback::NotifyVHACDComplete
virtual void NotifyVHACDComplete()
Definition: VHACD.h:345
VHACD::Vector3::GetY
T & GetY()
Definition: VHACD.h:541
VHACD::Vector3::operator+
Vector3 operator+(const Vector3 &rhs) const
Definition: VHACD.h:662
VHACD::Vector3::Vector3
Vector3()=default
VHACD::BoundsAABB::Inflate
BoundsAABB Inflate(double ratio) const
VHACD::BoundsAABB::GetSize
VHACD::Vect3 GetSize() const
VHACD::IVHACD::Release
virtual void Release()=0
VHACD::IVHACD::Parameters::m_resolution
uint32_t m_resolution
Definition: VHACD.h:398
VHACD::Vector3::~Vector3
~Vector3()=default
VHACD::Vertex
Definition: VHACD.h:134
VHACD::Triangle::mI2
uint32_t mI2
Definition: VHACD.h:162
VHACD::IVHACD::Parameters::m_maxConvexHulls
uint32_t m_maxConvexHulls
Definition: VHACD.h:397
VHACD::Vertex::mX
double mX
Definition: VHACD.h:136
VHACD::IVHACD::Parameters::m_maxRecursionDepth
uint32_t m_maxRecursionDepth
Definition: VHACD.h:401
VHACD::Vector3::operator/
Vector3 operator/(T rhs) const
Definition: VHACD.h:725
VHACD::IVHACD::Parameters::m_findBestPlane
bool m_findBestPlane
Definition: VHACD.h:408
VHACD::Vector3::GetX
T & GetX()
Definition: VHACD.h:535
VHACD::Vector3::LongestAxis
int LongestAxis() const
Definition: VHACD.h:605
operator-
template TMatrix3< double > operator-(const Matrix3< double > &m1, const TMatrix3< double > &m2)
VHACD::IVHACD::Parameters::m_minEdgeLength
uint32_t m_minEdgeLength
Definition: VHACD.h:406
VHACD::Vector3
Definition: VHACD.h:169
VHACD::IVHACD::Parameters::m_fillMode
FillMode m_fillMode
Definition: VHACD.h:403
VHACD::BoundsAABB::SurfaceArea
double SurfaceArea() const
VHACD::Vertex::mZ
double mZ
Definition: VHACD.h:138
VHACD::IVHACD::Parameters::m_minimumVolumePercentErrorAllowed
double m_minimumVolumePercentErrorAllowed
Definition: VHACD.h:399
VHACD::Vector3::operator+=
Vector3 & operator+=(const Vector3 &rhs)
Definition: VHACD.h:624
VHACD::Vector3::CWiseMax
Vector3 CWiseMax(const Vector3 &rhs) const
Definition: VHACD.h:789
VHACD::IVHACD::IUserTaskRunner::~IUserTaskRunner
virtual ~IUserTaskRunner()
Definition: VHACD.h:366
VHACD::IVHACD::ConvexHull
Definition: VHACD.h:375
VHACD::Vertex::operator[]
const double & operator[](size_t idx) const
Definition: VHACD.h:143
VHACD::Vector3::GetNorm
T GetNorm() const
Definition: VHACD.h:593
VHACD::Vector3::Normalized
Vector3 Normalized()
Definition: VHACD.h:583
VHACD::IVHACD::Parameters::m_logger
IUserLogger * m_logger
Definition: VHACD.h:395
VHACD::IVHACD::IUserTaskRunner::JoinTask
virtual void JoinTask(void *Task)=0
VHACD::IVHACD::ConvexHull::m_center
VHACD::Vect3 m_center
Definition: VHACD.h:382
VHACD::Triangle::mI1
uint32_t mI1
Definition: VHACD.h:161
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
VHACD::Vector3::operator=
Vector3 & operator=(const Vector3 &rhs)
Definition: VHACD.h:615
VHACD::Vector3::operator/=
Vector3 & operator/=(T a)
Definition: VHACD.h:701
VHACD::Vector3::operator-
Vector3 operator-() const
Definition: VHACD.h:734
VHACD::IVHACD::GetConvexHull
virtual bool GetConvexHull(const uint32_t index, ConvexHull &ch) const =0
VHACD::Triangle::Triangle
Triangle()=default
VHACD::IVHACD::IUserCallback::Update
virtual void Update(const double overallProgress, const double stageProgress, const char *const stage, const char *operation)=0
VHACD::IVHACD::Clean
virtual void Clean()=0
VHACD::FillMode::FLOOD_FILL
@ FLOOD_FILL
VHACD::Vector3::CWiseMul
Vector3 CWiseMul(const Vector3 &rhs) const
Definition: VHACD.h:642
VHACD::operator*
Vector3< T > operator*(T lhs, const Vector3< T > &rhs)
Definition: VHACD.h:674
VHACD::IVHACD::ConvexHull::m_volume
double m_volume
Definition: VHACD.h:381
VHACD::Vector3::GetNormSquared
T GetNormSquared() const
Definition: VHACD.h:599
VHACD::Vector3::MinCoeff
T MinCoeff() const
Definition: VHACD.h:795
VHACD::BoundsAABB::Intersects
bool Intersects(const BoundsAABB &b) const
VHACD::Vertex::Vertex
Vertex()=default
VHACD::IVHACD::~IVHACD
virtual ~IVHACD()
Definition: VHACD.h:499
hi
SaPCollisionManager< S >::EndPoint * hi
VHACD::BoundsAABB::ClosestPoint
VHACD::Vect3 ClosestPoint(const VHACD::Vect3 &p) const
VHACD::Vector3::operator[]
T & operator[](size_t i)
Definition: VHACD.h:523
VHACD::CreateVHACD_ASYNC
IVHACD * CreateVHACD_ASYNC()
VHACD::IVHACD::IsReady
virtual bool IsReady() const
Definition: VHACD.h:484
operator!=
bool operator!=(const ProfileDictionary &lhs, const ProfileDictionary &rhs)
VHACD::IVHACD::Parameters::m_taskRunner
IUserTaskRunner * m_taskRunner
Definition: VHACD.h:396
VHACD::IVHACD::IUserTaskRunner
Definition: VHACD.h:363
VHACD::IVHACD::IUserLogger::~IUserLogger
virtual ~IUserLogger()
Definition: VHACD.h:354
VHACD::IVHACD::Compute
virtual bool Compute(const float *const points, const uint32_t countPoints, const uint32_t *const triangles, const uint32_t countTriangles, const Parameters &params)=0
VHACD::FillMode
FillMode
Definition: VHACD.h:307
operator==
bool operator==(const AllowedCollisionEntries &entries_1, const AllowedCollisionEntries &entries_2)
VHACD::Vector3::Dot
T Dot(const Vector3 &rhs) const
Definition: VHACD.h:656
VHACD::Vector3::CWiseAllLE
bool CWiseAllLE(const Vector3< T > &rhs) const
Definition: VHACD.h:777
VHACD::Vertex::mY
double mY
Definition: VHACD.h:137
VHACD::Triangle::mI0
uint32_t mI0
Definition: VHACD.h:160
VHACD::Vector3::Cross
Vector3 Cross(const Vector3 &rhs) const
Definition: VHACD.h:648
VHACD::IVHACD::GetNConvexHulls
virtual uint32_t GetNConvexHulls() const =0
VHACD::IVHACD::ConvexHull::m_meshId
uint32_t m_meshId
Definition: VHACD.h:383
VHACD::BoundsAABB::m_min
VHACD::Vect3 m_min
Definition: VHACD.h:291
VHACD::BoundsAABB::GetCenter
VHACD::Vect3 GetCenter() const
VHACD::Vector3::Normalize
T Normalize()
Definition: VHACD.h:574
VHACD::IVHACD::ConvexHull::mBmin
VHACD::Vect3 mBmin
Definition: VHACD.h:384
VHACD::BoundsAABB::BoundsAABB
BoundsAABB()=default
VHACD::IVHACD::ConvexHull::m_points
std::vector< VHACD::Vertex > m_points
Definition: VHACD.h:378
VHACD::IVHACD::IUserLogger::Log
virtual void Log(const char *const msg)=0
r
S r
VHACD::FillMode::RAYCAST_FILL
@ RAYCAST_FILL
VHACD::IVHACD::Parameters::m_callback
IUserCallback * m_callback
Definition: VHACD.h:394
VHACD::Triangle::Triangle
Triangle(uint32_t i0, uint32_t i1, uint32_t i2)
Definition: VHACD.h:165
VHACD::BoundsAABB::Volume
double Volume() const
VHACD::BoundsAABB::Union
BoundsAABB Union(const BoundsAABB &b)
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
VHACD::IVHACD::Parameters
Definition: VHACD.h:391
VHACD::IVHACD::Cancel
virtual void Cancel()=0
VHACD::Vector3::MaxCoeff
T MaxCoeff() const
Definition: VHACD.h:801
VHACD::Triangle
Definition: VHACD.h:158
point
std::chrono::system_clock::time_point point
VHACD::IVHACD::Parameters::m_maxNumVerticesPerCH
uint32_t m_maxNumVerticesPerCH
Definition: VHACD.h:404
VHACD::Vect3
VHACD::Vector3< double > Vect3
Definition: VHACD.h:264
VHACD::CreateVHACD
IVHACD * CreateVHACD()
VHACD::Vector3::operator>
bool operator>(const Vector3 &rhs) const
Definition: VHACD.h:757
VHACD::IVHACD::IUserCallback::~IUserCallback
virtual ~IUserCallback()
Definition: VHACD.h:326
now
FCL_EXPORT point now(void)
VHACD::Vector3::operator*
Vector3 operator*(T rhs) const
Definition: VHACD.h:719
VHACD::FillMode::SURFACE_ONLY
@ SURFACE_ONLY
VHACD::Vertex::Vertex
Vertex(double x, double y, double z)
Definition: VHACD.h:141
VHACD::Vector3::CWiseMin
Vector3 CWiseMin(const Vector3 &rhs) const
Definition: VHACD.h:783
VHACD::Vector3::operator*=
Vector3 & operator*=(T a)
Definition: VHACD.h:710
VHACD::Vector3::CWiseAllGE
bool CWiseAllGE(const Vector3< T > &rhs) const
Definition: VHACD.h:771
VHACD::IVHACD::findNearestConvexHull
virtual uint32_t findNearestConvexHull(const double pos[3], double &distanceToHull)=0
VHACD::IVHACD::ConvexHull::mBmax
VHACD::Vect3 mBmax
Definition: VHACD.h:385
VHACD::IVHACD::Parameters::m_shrinkWrap
bool m_shrinkWrap
Definition: VHACD.h:402
lo
SaPCollisionManager< S >::EndPoint * lo
VHACD
Definition: VHACD.h:132
VHACD::BoundsAABB::GetMax
VHACD::Vect3 & GetMax()
VHACD::Vector3::operator-=
Vector3 & operator-=(const Vector3 &rhs)
Definition: VHACD.h:633
VHACD::IVHACD::ConvexHull::m_triangles
std::vector< VHACD::Triangle > m_triangles
Definition: VHACD.h:379
VHACD::BoundsAABB::GetMin
VHACD::Vect3 & GetMin()
VHACD::Vector3::GetZ
T & GetZ()
Definition: VHACD.h:547
VHACD::IVHACD::IUserLogger
Definition: VHACD.h:351
VHACD::IVHACD::ComputeCenterOfMass
virtual bool ComputeCenterOfMass(double centerOfMass[3]) const =0
VHACD::Vector3::m_data
std::array< T, 3 > m_data
Definition: VHACD.h:261
VHACD::BoundsAABB
Definition: VHACD.h:266
macros.h
VHACD::Vector3::operator<
bool operator<(const Vector3 &rhs) const
Definition: VHACD.h:743
VHACD::IVHACD::IUserCallback
Definition: VHACD.h:323
VHACD::clamp
T clamp(const T &v, const T &lo, const T &hi)
Definition: VHACD.h:506
VHACD::IVHACD::Parameters::m_asyncACD
bool m_asyncACD
Definition: VHACD.h:405
VHACD::IVHACD
Definition: VHACD.h:315
VHACD::BoundsAABB::m_max
VHACD::Vect3 m_max
Definition: VHACD.h:292
VHACD::IVHACD::IUserTaskRunner::StartTask
virtual void * StartTask(std::function< void()> func)=0
operator+
template TMatrix3< double > operator+(const Matrix3< double > &m1, const TMatrix3< double > &m2)


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:53