initial commit, 4.5 stable
Some checks failed
🔗 GHA / 📊 Static checks (push) Has been cancelled
🔗 GHA / 🤖 Android (push) Has been cancelled
🔗 GHA / 🍏 iOS (push) Has been cancelled
🔗 GHA / 🐧 Linux (push) Has been cancelled
🔗 GHA / 🍎 macOS (push) Has been cancelled
🔗 GHA / 🏁 Windows (push) Has been cancelled
🔗 GHA / 🌐 Web (push) Has been cancelled

This commit is contained in:
2025-09-16 20:46:46 -04:00
commit 9d30169a8d
13378 changed files with 7050105 additions and 0 deletions

17
thirdparty/vhacd/src/FloatMath.cpp vendored Normal file
View File

@@ -0,0 +1,17 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <assert.h>
#include <math.h>
#include <float.h>
#include "FloatMath.h"
#include <vector>
#define REAL float
#include "FloatMath.inl"
#undef REAL
#define REAL double
#include "FloatMath.inl"

5280
thirdparty/vhacd/src/FloatMath.inl vendored Normal file

File diff suppressed because it is too large Load Diff

334
thirdparty/vhacd/src/VHACD-ASYNC.cpp vendored Normal file
View File

@@ -0,0 +1,334 @@
#include "../public/VHACD.h"
#include <stdlib.h>
#include <string.h>
#include <stdarg.h>
#include <thread>
#include <atomic>
#include <mutex>
#include <string>
#include <float.h>
#define ENABLE_ASYNC 1
#define HACD_ALLOC(x) malloc(x)
#define HACD_FREE(x) free(x)
#define HACD_ASSERT(x) assert(x)
namespace VHACD
{
class MyHACD_API : public VHACD::IVHACD, public VHACD::IVHACD::IUserCallback, VHACD::IVHACD::IUserLogger
{
public:
MyHACD_API(void)
{
mVHACD = VHACD::CreateVHACD();
}
virtual ~MyHACD_API(void)
{
releaseHACD();
Cancel();
mVHACD->Release();
}
virtual bool Compute(const double* const _points,
const uint32_t countPoints,
const uint32_t* const _triangles,
const uint32_t countTriangles,
const Parameters& _desc) final
{
#if ENABLE_ASYNC
Cancel(); // if we previously had a solution running; cancel it.
releaseHACD();
// We need to copy the input vertices and triangles into our own buffers so we can operate
// on them safely from the background thread.
mVertices = (double *)HACD_ALLOC(sizeof(double)*countPoints * 3);
mIndices = (uint32_t *)HACD_ALLOC(sizeof(uint32_t)*countTriangles * 3);
memcpy(mVertices, _points, sizeof(double)*countPoints * 3);
memcpy(mIndices, _triangles, sizeof(uint32_t)*countTriangles * 3);
mRunning = true;
mThread = new std::thread([this, countPoints, countTriangles, _desc]()
{
ComputeNow(mVertices, countPoints, mIndices, countTriangles, _desc);
mRunning = false;
});
#else
releaseHACD();
ComputeNow(_points, countPoints, _triangles, countTriangles, _desc);
#endif
return true;
}
bool ComputeNow(const double* const points,
const uint32_t countPoints,
const uint32_t* const triangles,
const uint32_t countTriangles,
const Parameters& _desc)
{
uint32_t ret = 0;
mHullCount = 0;
mCallback = _desc.m_callback;
mLogger = _desc.m_logger;
IVHACD::Parameters desc = _desc;
// Set our intercepting callback interfaces if non-null
desc.m_callback = desc.m_callback ? this : nullptr;
desc.m_logger = desc.m_logger ? this : nullptr;
if ( countPoints )
{
bool ok = mVHACD->Compute(points, countPoints, triangles, countTriangles, desc);
if (ok)
{
ret = mVHACD->GetNConvexHulls();
mHulls = new IVHACD::ConvexHull[ret];
for (uint32_t i = 0; i < ret; i++)
{
VHACD::IVHACD::ConvexHull vhull;
mVHACD->GetConvexHull(i, vhull);
VHACD::IVHACD::ConvexHull h;
h.m_nPoints = vhull.m_nPoints;
h.m_points = (double *)HACD_ALLOC(sizeof(double) * 3 * h.m_nPoints);
memcpy(h.m_points, vhull.m_points, sizeof(double) * 3 * h.m_nPoints);
h.m_nTriangles = vhull.m_nTriangles;
h.m_triangles = (uint32_t *)HACD_ALLOC(sizeof(uint32_t) * 3 * h.m_nTriangles);
memcpy(h.m_triangles, vhull.m_triangles, sizeof(uint32_t) * 3 * h.m_nTriangles);
h.m_volume = vhull.m_volume;
h.m_center[0] = vhull.m_center[0];
h.m_center[1] = vhull.m_center[1];
h.m_center[2] = vhull.m_center[2];
mHulls[i] = h;
if (mCancel)
{
ret = 0;
break;
}
}
}
}
mHullCount = ret;
return ret ? true : false;
}
void releaseHull(VHACD::IVHACD::ConvexHull &h)
{
HACD_FREE((void *)h.m_triangles);
HACD_FREE((void *)h.m_points);
h.m_triangles = nullptr;
h.m_points = nullptr;
}
virtual void GetConvexHull(const uint32_t index, VHACD::IVHACD::ConvexHull& ch) const final
{
if ( index < mHullCount )
{
ch = mHulls[index];
}
}
void releaseHACD(void) // release memory associated with the last HACD request
{
for (uint32_t i=0; i<mHullCount; i++)
{
releaseHull(mHulls[i]);
}
delete[]mHulls;
mHulls = nullptr;
mHullCount = 0;
HACD_FREE(mVertices);
mVertices = nullptr;
HACD_FREE(mIndices);
mIndices = nullptr;
}
virtual void release(void) // release the HACD_API interface
{
delete this;
}
virtual uint32_t getHullCount(void)
{
return mHullCount;
}
virtual void Cancel() final
{
if (mRunning)
{
mVHACD->Cancel(); // Set the cancel signal to the base VHACD
}
if (mThread)
{
mThread->join(); // Wait for the thread to fully exit before we delete the instance
delete mThread;
mThread = nullptr;
Log("Convex Decomposition thread canceled\n");
}
mCancel = false; // clear the cancel semaphore
}
virtual bool Compute(const float* const points,
const uint32_t countPoints,
const uint32_t* const triangles,
const uint32_t countTriangles,
const Parameters& params) final
{
double *vertices = (double *)HACD_ALLOC(sizeof(double)*countPoints * 3);
const float *source = points;
double *dest = vertices;
for (uint32_t i = 0; i < countPoints; i++)
{
dest[0] = source[0];
dest[1] = source[1];
dest[2] = source[2];
dest += 3;
source += 3;
}
bool ret = Compute(vertices, countPoints, triangles, countTriangles, params);
HACD_FREE(vertices);
return ret;
}
virtual uint32_t GetNConvexHulls() const final
{
processPendingMessages();
return mHullCount;
}
virtual void Clean(void) final // release internally allocated memory
{
Cancel();
releaseHACD();
mVHACD->Clean();
}
virtual void Release(void) final // release IVHACD
{
delete this;
}
virtual bool OCLInit(void* const oclDevice,
IVHACD::IUserLogger* const logger = 0) final
{
return mVHACD->OCLInit(oclDevice, logger);
}
virtual bool OCLRelease(IVHACD::IUserLogger* const logger = 0) final
{
return mVHACD->OCLRelease(logger);
}
virtual void Update(const double overallProgress,
const double stageProgress,
const double operationProgress,
const char* const stage,
const char* const operation) final
{
mMessageMutex.lock();
mHaveUpdateMessage = true;
mOverallProgress = overallProgress;
mStageProgress = stageProgress;
mOperationProgress = operationProgress;
mStage = std::string(stage);
mOperation = std::string(operation);
mMessageMutex.unlock();
}
virtual void Log(const char* const msg) final
{
mMessageMutex.lock();
mHaveLogMessage = true;
mMessage = std::string(msg);
mMessageMutex.unlock();
}
virtual bool IsReady(void) const final
{
processPendingMessages();
return !mRunning;
}
// As a convenience for the calling application we only send it update and log messages from it's own main
// thread. This reduces the complexity burden on the caller by making sure it only has to deal with log
// messages in it's main application thread.
void processPendingMessages(void) const
{
// If we have a new update message and the user has specified a callback we send the message and clear the semaphore
if (mHaveUpdateMessage && mCallback)
{
mMessageMutex.lock();
mCallback->Update(mOverallProgress, mStageProgress, mOperationProgress, mStage.c_str(), mOperation.c_str());
mHaveUpdateMessage = false;
mMessageMutex.unlock();
}
// If we have a new log message and the user has specified a callback we send the message and clear the semaphore
if (mHaveLogMessage && mLogger)
{
mMessageMutex.lock();
mLogger->Log(mMessage.c_str());
mHaveLogMessage = false;
mMessageMutex.unlock();
}
}
// Will compute the center of mass of the convex hull decomposition results and return it
// in 'centerOfMass'. Returns false if the center of mass could not be computed.
virtual bool ComputeCenterOfMass(double centerOfMass[3]) const
{
bool ret = false;
centerOfMass[0] = 0;
centerOfMass[1] = 0;
centerOfMass[2] = 0;
if (mVHACD && IsReady() )
{
ret = mVHACD->ComputeCenterOfMass(centerOfMass);
}
return ret;
}
private:
double *mVertices{ nullptr };
uint32_t *mIndices{ nullptr };
std::atomic< uint32_t> mHullCount{ 0 };
VHACD::IVHACD::ConvexHull *mHulls{ nullptr };
VHACD::IVHACD::IUserCallback *mCallback{ nullptr };
VHACD::IVHACD::IUserLogger *mLogger{ nullptr };
VHACD::IVHACD *mVHACD{ nullptr };
std::thread *mThread{ nullptr };
std::atomic< bool > mRunning{ false };
std::atomic<bool> mCancel{ false };
// Thread safe caching mechanism for messages and update status.
// This is so that caller always gets messages in his own thread
// Member variables are marked as 'mutable' since the message dispatch function
// is called from const query methods.
mutable std::mutex mMessageMutex;
mutable std::atomic< bool > mHaveUpdateMessage{ false };
mutable std::atomic< bool > mHaveLogMessage{ false };
mutable double mOverallProgress{ 0 };
mutable double mStageProgress{ 0 };
mutable double mOperationProgress{ 0 };
mutable std::string mStage;
mutable std::string mOperation;
mutable std::string mMessage;
};
IVHACD* CreateVHACD_ASYNC(void)
{
MyHACD_API *m = new MyHACD_API;
return static_cast<IVHACD *>(m);
}
}; // end of VHACD namespace

1589
thirdparty/vhacd/src/VHACD.cpp vendored Normal file

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,186 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "btAlignedAllocator.h"
namespace VHACD {
#ifdef _MSC_VER
#pragma warning(disable:4311 4302)
#endif
int32_t gNumAlignedAllocs = 0;
int32_t gNumAlignedFree = 0;
int32_t gTotalBytesAlignedAllocs = 0; //detect memory leaks
static void* btAllocDefault(size_t size)
{
return malloc(size);
}
static void btFreeDefault(void* ptr)
{
free(ptr);
}
static btAllocFunc* sAllocFunc = btAllocDefault;
static btFreeFunc* sFreeFunc = btFreeDefault;
#if defined(BT_HAS_ALIGNED_ALLOCATOR)
#include <malloc.h>
static void* btAlignedAllocDefault(size_t size, int32_t alignment)
{
return _aligned_malloc(size, (size_t)alignment);
}
static void btAlignedFreeDefault(void* ptr)
{
_aligned_free(ptr);
}
#elif defined(__CELLOS_LV2__)
#include <stdlib.h>
static inline void* btAlignedAllocDefault(size_t size, int32_t alignment)
{
return memalign(alignment, size);
}
static inline void btAlignedFreeDefault(void* ptr)
{
free(ptr);
}
#else
static inline void* btAlignedAllocDefault(size_t size, int32_t alignment)
{
void* ret;
char* real;
unsigned long offset;
real = (char*)sAllocFunc(size + sizeof(void*) + (alignment - 1));
if (real) {
// Synced with Bullet 2.88 to fix GH-27926
//offset = (alignment - (unsigned long)(real + sizeof(void*))) & (alignment - 1);
//ret = (void*)((real + sizeof(void*)) + offset);
ret = btAlignPointer(real + sizeof(void *), alignment);
*((void**)(ret)-1) = (void*)(real);
}
else {
ret = (void*)(real);
}
return (ret);
}
static inline void btAlignedFreeDefault(void* ptr)
{
void* real;
if (ptr) {
real = *((void**)(ptr)-1);
sFreeFunc(real);
}
}
#endif
static btAlignedAllocFunc* sAlignedAllocFunc = btAlignedAllocDefault;
static btAlignedFreeFunc* sAlignedFreeFunc = btAlignedFreeDefault;
void btAlignedAllocSetCustomAligned(btAlignedAllocFunc* allocFunc, btAlignedFreeFunc* freeFunc)
{
sAlignedAllocFunc = allocFunc ? allocFunc : btAlignedAllocDefault;
sAlignedFreeFunc = freeFunc ? freeFunc : btAlignedFreeDefault;
}
void btAlignedAllocSetCustom(btAllocFunc* allocFunc, btFreeFunc* freeFunc)
{
sAllocFunc = allocFunc ? allocFunc : btAllocDefault;
sFreeFunc = freeFunc ? freeFunc : btFreeDefault;
}
#ifdef BT_DEBUG_MEMORY_ALLOCATIONS
//this generic allocator provides the total allocated number of bytes
#include <stdio.h>
void* btAlignedAllocInternal(size_t size, int32_t alignment, int32_t line, char* filename)
{
void* ret;
char* real;
unsigned long offset;
gTotalBytesAlignedAllocs += size;
gNumAlignedAllocs++;
real = (char*)sAllocFunc(size + 2 * sizeof(void*) + (alignment - 1));
if (real) {
offset = (alignment - (unsigned long)(real + 2 * sizeof(void*))) & (alignment - 1);
ret = (void*)((real + 2 * sizeof(void*)) + offset);
*((void**)(ret)-1) = (void*)(real);
*((int32_t*)(ret)-2) = size;
}
else {
ret = (void*)(real); //??
}
printf("allocation#%d at address %x, from %s,line %d, size %d\n", gNumAlignedAllocs, real, filename, line, size);
int32_t* ptr = (int32_t*)ret;
*ptr = 12;
return (ret);
}
void btAlignedFreeInternal(void* ptr, int32_t line, char* filename)
{
void* real;
gNumAlignedFree++;
if (ptr) {
real = *((void**)(ptr)-1);
int32_t size = *((int32_t*)(ptr)-2);
gTotalBytesAlignedAllocs -= size;
printf("free #%d at address %x, from %s,line %d, size %d\n", gNumAlignedFree, real, filename, line, size);
sFreeFunc(real);
}
else {
printf("NULL ptr\n");
}
}
#else //BT_DEBUG_MEMORY_ALLOCATIONS
void* btAlignedAllocInternal(size_t size, int32_t alignment)
{
gNumAlignedAllocs++;
void* ptr;
ptr = sAlignedAllocFunc(size, alignment);
// printf("btAlignedAllocInternal %d, %x\n",size,ptr);
return ptr;
}
void btAlignedFreeInternal(void* ptr)
{
if (!ptr) {
return;
}
gNumAlignedFree++;
// printf("btAlignedFreeInternal %x\n",ptr);
sAlignedFreeFunc(ptr);
}
}; // namespace VHACD
#endif //BT_DEBUG_MEMORY_ALLOCATIONS

File diff suppressed because it is too large Load Diff

731
thirdparty/vhacd/src/vhacdICHull.cpp vendored Normal file
View File

@@ -0,0 +1,731 @@
/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com)
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "vhacdICHull.h"
#include <limits>
#ifdef _MSC_VER
#pragma warning(disable:4456 4706)
#endif
namespace VHACD {
const double ICHull::sc_eps = 1.0e-15;
const int32_t ICHull::sc_dummyIndex = std::numeric_limits<int32_t>::max();
ICHull::ICHull()
{
m_isFlat = false;
}
bool ICHull::AddPoints(const Vec3<double>* points, size_t nPoints)
{
if (!points) {
return false;
}
CircularListElement<TMMVertex>* vertex = NULL;
for (size_t i = 0; i < nPoints; i++) {
vertex = m_mesh.AddVertex();
vertex->GetData().m_pos.X() = points[i].X();
vertex->GetData().m_pos.Y() = points[i].Y();
vertex->GetData().m_pos.Z() = points[i].Z();
vertex->GetData().m_name = static_cast<int32_t>(i);
}
return true;
}
bool ICHull::AddPoint(const Vec3<double>& point, int32_t id)
{
if (AddPoints(&point, 1)) {
m_mesh.m_vertices.GetData().m_name = id;
return true;
}
return false;
}
ICHullError ICHull::Process()
{
uint32_t addedPoints = 0;
if (m_mesh.GetNVertices() < 3) {
return ICHullErrorNotEnoughPoints;
}
if (m_mesh.GetNVertices() == 3) {
m_isFlat = true;
CircularListElement<TMMTriangle>* t1 = m_mesh.AddTriangle();
CircularListElement<TMMTriangle>* t2 = m_mesh.AddTriangle();
CircularListElement<TMMVertex>* v0 = m_mesh.m_vertices.GetHead();
CircularListElement<TMMVertex>* v1 = v0->GetNext();
CircularListElement<TMMVertex>* v2 = v1->GetNext();
// Compute the normal to the plane
Vec3<double> p0 = v0->GetData().m_pos;
Vec3<double> p1 = v1->GetData().m_pos;
Vec3<double> p2 = v2->GetData().m_pos;
m_normal = (p1 - p0) ^ (p2 - p0);
m_normal.Normalize();
t1->GetData().m_vertices[0] = v0;
t1->GetData().m_vertices[1] = v1;
t1->GetData().m_vertices[2] = v2;
t2->GetData().m_vertices[0] = v1;
t2->GetData().m_vertices[1] = v2;
t2->GetData().m_vertices[2] = v2;
return ICHullErrorOK;
}
if (m_isFlat) {
m_mesh.m_edges.Clear();
m_mesh.m_triangles.Clear();
m_isFlat = false;
}
if (m_mesh.GetNTriangles() == 0) // we have to create the first polyhedron
{
ICHullError res = DoubleTriangle();
if (res != ICHullErrorOK) {
return res;
}
else {
addedPoints += 3;
}
}
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
// go to the first added and not processed vertex
while (!(vertices.GetHead()->GetPrev()->GetData().m_tag)) {
vertices.Prev();
}
while (!vertices.GetData().m_tag) // not processed
{
vertices.GetData().m_tag = true;
if (ProcessPoint()) {
addedPoints++;
CleanUp(addedPoints);
vertices.Next();
if (!GetMesh().CheckConsistancy()) {
size_t nV = m_mesh.GetNVertices();
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
for (size_t v = 0; v < nV; ++v) {
if (vertices.GetData().m_name == sc_dummyIndex) {
vertices.Delete();
break;
}
vertices.Next();
}
return ICHullErrorInconsistent;
}
}
}
if (m_isFlat) {
SArray<CircularListElement<TMMTriangle>*> trianglesToDuplicate;
size_t nT = m_mesh.GetNTriangles();
for (size_t f = 0; f < nT; f++) {
TMMTriangle& currentTriangle = m_mesh.m_triangles.GetHead()->GetData();
if (currentTriangle.m_vertices[0]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[1]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[2]->GetData().m_name == sc_dummyIndex) {
m_trianglesToDelete.PushBack(m_mesh.m_triangles.GetHead());
for (int32_t k = 0; k < 3; k++) {
for (int32_t h = 0; h < 2; h++) {
if (currentTriangle.m_edges[k]->GetData().m_triangles[h] == m_mesh.m_triangles.GetHead()) {
currentTriangle.m_edges[k]->GetData().m_triangles[h] = 0;
break;
}
}
}
}
else {
trianglesToDuplicate.PushBack(m_mesh.m_triangles.GetHead());
}
m_mesh.m_triangles.Next();
}
size_t nE = m_mesh.GetNEdges();
for (size_t e = 0; e < nE; e++) {
TMMEdge& currentEdge = m_mesh.m_edges.GetHead()->GetData();
if (currentEdge.m_triangles[0] == 0 && currentEdge.m_triangles[1] == 0) {
m_edgesToDelete.PushBack(m_mesh.m_edges.GetHead());
}
m_mesh.m_edges.Next();
}
size_t nV = m_mesh.GetNVertices();
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
for (size_t v = 0; v < nV; ++v) {
if (vertices.GetData().m_name == sc_dummyIndex) {
vertices.Delete();
}
else {
vertices.GetData().m_tag = false;
vertices.Next();
}
}
CleanEdges();
CleanTriangles();
CircularListElement<TMMTriangle>* newTriangle;
for (size_t t = 0; t < trianglesToDuplicate.Size(); t++) {
newTriangle = m_mesh.AddTriangle();
newTriangle->GetData().m_vertices[0] = trianglesToDuplicate[t]->GetData().m_vertices[1];
newTriangle->GetData().m_vertices[1] = trianglesToDuplicate[t]->GetData().m_vertices[0];
newTriangle->GetData().m_vertices[2] = trianglesToDuplicate[t]->GetData().m_vertices[2];
}
}
return ICHullErrorOK;
}
ICHullError ICHull::Process(const uint32_t nPointsCH,
const double minVolume)
{
uint32_t addedPoints = 0;
if (nPointsCH < 3 || m_mesh.GetNVertices() < 3) {
return ICHullErrorNotEnoughPoints;
}
if (m_mesh.GetNVertices() == 3) {
m_isFlat = true;
CircularListElement<TMMTriangle>* t1 = m_mesh.AddTriangle();
CircularListElement<TMMTriangle>* t2 = m_mesh.AddTriangle();
CircularListElement<TMMVertex>* v0 = m_mesh.m_vertices.GetHead();
CircularListElement<TMMVertex>* v1 = v0->GetNext();
CircularListElement<TMMVertex>* v2 = v1->GetNext();
// Compute the normal to the plane
Vec3<double> p0 = v0->GetData().m_pos;
Vec3<double> p1 = v1->GetData().m_pos;
Vec3<double> p2 = v2->GetData().m_pos;
m_normal = (p1 - p0) ^ (p2 - p0);
m_normal.Normalize();
t1->GetData().m_vertices[0] = v0;
t1->GetData().m_vertices[1] = v1;
t1->GetData().m_vertices[2] = v2;
t2->GetData().m_vertices[0] = v1;
t2->GetData().m_vertices[1] = v0;
t2->GetData().m_vertices[2] = v2;
return ICHullErrorOK;
}
if (m_isFlat) {
m_mesh.m_triangles.Clear();
m_mesh.m_edges.Clear();
m_isFlat = false;
}
if (m_mesh.GetNTriangles() == 0) // we have to create the first polyhedron
{
ICHullError res = DoubleTriangle();
if (res != ICHullErrorOK) {
return res;
}
else {
addedPoints += 3;
}
}
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
while (!vertices.GetData().m_tag && addedPoints < nPointsCH) // not processed
{
if (!FindMaxVolumePoint((addedPoints > 4) ? minVolume : 0.0)) {
break;
}
vertices.GetData().m_tag = true;
if (ProcessPoint()) {
addedPoints++;
CleanUp(addedPoints);
if (!GetMesh().CheckConsistancy()) {
size_t nV = m_mesh.GetNVertices();
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
for (size_t v = 0; v < nV; ++v) {
if (vertices.GetData().m_name == sc_dummyIndex) {
vertices.Delete();
break;
}
vertices.Next();
}
return ICHullErrorInconsistent;
}
vertices.Next();
}
}
// delete remaining points
while (!vertices.GetData().m_tag) {
vertices.Delete();
}
if (m_isFlat) {
SArray<CircularListElement<TMMTriangle>*> trianglesToDuplicate;
size_t nT = m_mesh.GetNTriangles();
for (size_t f = 0; f < nT; f++) {
TMMTriangle& currentTriangle = m_mesh.m_triangles.GetHead()->GetData();
if (currentTriangle.m_vertices[0]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[1]->GetData().m_name == sc_dummyIndex || currentTriangle.m_vertices[2]->GetData().m_name == sc_dummyIndex) {
m_trianglesToDelete.PushBack(m_mesh.m_triangles.GetHead());
for (int32_t k = 0; k < 3; k++) {
for (int32_t h = 0; h < 2; h++) {
if (currentTriangle.m_edges[k]->GetData().m_triangles[h] == m_mesh.m_triangles.GetHead()) {
currentTriangle.m_edges[k]->GetData().m_triangles[h] = 0;
break;
}
}
}
}
else {
trianglesToDuplicate.PushBack(m_mesh.m_triangles.GetHead());
}
m_mesh.m_triangles.Next();
}
size_t nE = m_mesh.GetNEdges();
for (size_t e = 0; e < nE; e++) {
TMMEdge& currentEdge = m_mesh.m_edges.GetHead()->GetData();
if (currentEdge.m_triangles[0] == 0 && currentEdge.m_triangles[1] == 0) {
m_edgesToDelete.PushBack(m_mesh.m_edges.GetHead());
}
m_mesh.m_edges.Next();
}
size_t nV = m_mesh.GetNVertices();
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
for (size_t v = 0; v < nV; ++v) {
if (vertices.GetData().m_name == sc_dummyIndex) {
vertices.Delete();
}
else {
vertices.GetData().m_tag = false;
vertices.Next();
}
}
CleanEdges();
CleanTriangles();
CircularListElement<TMMTriangle>* newTriangle;
for (size_t t = 0; t < trianglesToDuplicate.Size(); t++) {
newTriangle = m_mesh.AddTriangle();
newTriangle->GetData().m_vertices[0] = trianglesToDuplicate[t]->GetData().m_vertices[1];
newTriangle->GetData().m_vertices[1] = trianglesToDuplicate[t]->GetData().m_vertices[0];
newTriangle->GetData().m_vertices[2] = trianglesToDuplicate[t]->GetData().m_vertices[2];
}
}
return ICHullErrorOK;
}
bool ICHull::FindMaxVolumePoint(const double minVolume)
{
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
CircularListElement<TMMVertex>* vMaxVolume = 0;
CircularListElement<TMMVertex>* vHeadPrev = vertices.GetHead()->GetPrev();
double maxVolume = minVolume;
double volume = 0.0;
while (!vertices.GetData().m_tag) // not processed
{
if (ComputePointVolume(volume, false)) {
if (maxVolume < volume) {
maxVolume = volume;
vMaxVolume = vertices.GetHead();
}
vertices.Next();
}
}
CircularListElement<TMMVertex>* vHead = vHeadPrev->GetNext();
vertices.GetHead() = vHead;
if (!vMaxVolume) {
return false;
}
if (vMaxVolume != vHead) {
Vec3<double> pos = vHead->GetData().m_pos;
int32_t id = vHead->GetData().m_name;
vHead->GetData().m_pos = vMaxVolume->GetData().m_pos;
vHead->GetData().m_name = vMaxVolume->GetData().m_name;
vMaxVolume->GetData().m_pos = pos;
vHead->GetData().m_name = id;
}
return true;
}
ICHullError ICHull::DoubleTriangle()
{
// find three non colinear points
m_isFlat = false;
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
CircularListElement<TMMVertex>* v0 = vertices.GetHead();
while (Colinear(v0->GetData().m_pos,
v0->GetNext()->GetData().m_pos,
v0->GetNext()->GetNext()->GetData().m_pos)) {
if ((v0 = v0->GetNext()) == vertices.GetHead()) {
return ICHullErrorCoplanarPoints;
}
}
CircularListElement<TMMVertex>* v1 = v0->GetNext();
CircularListElement<TMMVertex>* v2 = v1->GetNext();
// mark points as processed
v0->GetData().m_tag = v1->GetData().m_tag = v2->GetData().m_tag = true;
// create two triangles
CircularListElement<TMMTriangle>* f0 = MakeFace(v0, v1, v2, 0);
MakeFace(v2, v1, v0, f0);
// find a fourth non-coplanar point to form tetrahedron
CircularListElement<TMMVertex>* v3 = v2->GetNext();
vertices.GetHead() = v3;
double vol = ComputeVolume4(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos);
while (fabs(vol) < sc_eps && !v3->GetNext()->GetData().m_tag) {
v3 = v3->GetNext();
vol = ComputeVolume4(v0->GetData().m_pos, v1->GetData().m_pos, v2->GetData().m_pos, v3->GetData().m_pos);
}
if (fabs(vol) < sc_eps) {
// compute the barycenter
Vec3<double> bary(0.0, 0.0, 0.0);
CircularListElement<TMMVertex>* vBary = v0;
do {
bary += vBary->GetData().m_pos;
} while ((vBary = vBary->GetNext()) != v0);
bary /= static_cast<double>(vertices.GetSize());
// Compute the normal to the plane
Vec3<double> p0 = v0->GetData().m_pos;
Vec3<double> p1 = v1->GetData().m_pos;
Vec3<double> p2 = v2->GetData().m_pos;
m_normal = (p1 - p0) ^ (p2 - p0);
m_normal.Normalize();
// add dummy vertex placed at (bary + normal)
vertices.GetHead() = v2;
Vec3<double> newPt = bary + m_normal;
AddPoint(newPt, sc_dummyIndex);
m_isFlat = true;
return ICHullErrorOK;
}
else if (v3 != vertices.GetHead()) {
TMMVertex temp;
temp.m_name = v3->GetData().m_name;
temp.m_pos = v3->GetData().m_pos;
v3->GetData().m_name = vertices.GetHead()->GetData().m_name;
v3->GetData().m_pos = vertices.GetHead()->GetData().m_pos;
vertices.GetHead()->GetData().m_name = temp.m_name;
vertices.GetHead()->GetData().m_pos = temp.m_pos;
}
return ICHullErrorOK;
}
CircularListElement<TMMTriangle>* ICHull::MakeFace(CircularListElement<TMMVertex>* v0,
CircularListElement<TMMVertex>* v1,
CircularListElement<TMMVertex>* v2,
CircularListElement<TMMTriangle>* fold)
{
CircularListElement<TMMEdge>* e0;
CircularListElement<TMMEdge>* e1;
CircularListElement<TMMEdge>* e2;
int32_t index = 0;
if (!fold) // if first face to be created
{
e0 = m_mesh.AddEdge(); // create the three edges
e1 = m_mesh.AddEdge();
e2 = m_mesh.AddEdge();
}
else // otherwise re-use existing edges (in reverse order)
{
e0 = fold->GetData().m_edges[2];
e1 = fold->GetData().m_edges[1];
e2 = fold->GetData().m_edges[0];
index = 1;
}
e0->GetData().m_vertices[0] = v0;
e0->GetData().m_vertices[1] = v1;
e1->GetData().m_vertices[0] = v1;
e1->GetData().m_vertices[1] = v2;
e2->GetData().m_vertices[0] = v2;
e2->GetData().m_vertices[1] = v0;
// create the new face
CircularListElement<TMMTriangle>* f = m_mesh.AddTriangle();
f->GetData().m_edges[0] = e0;
f->GetData().m_edges[1] = e1;
f->GetData().m_edges[2] = e2;
f->GetData().m_vertices[0] = v0;
f->GetData().m_vertices[1] = v1;
f->GetData().m_vertices[2] = v2;
// link edges to face f
e0->GetData().m_triangles[index] = e1->GetData().m_triangles[index] = e2->GetData().m_triangles[index] = f;
return f;
}
CircularListElement<TMMTriangle>* ICHull::MakeConeFace(CircularListElement<TMMEdge>* e, CircularListElement<TMMVertex>* p)
{
// create two new edges if they don't already exist
CircularListElement<TMMEdge>* newEdges[2];
for (int32_t i = 0; i < 2; ++i) {
if (!(newEdges[i] = e->GetData().m_vertices[i]->GetData().m_duplicate)) { // if the edge doesn't exits add it and mark the vertex as duplicated
newEdges[i] = m_mesh.AddEdge();
newEdges[i]->GetData().m_vertices[0] = e->GetData().m_vertices[i];
newEdges[i]->GetData().m_vertices[1] = p;
e->GetData().m_vertices[i]->GetData().m_duplicate = newEdges[i];
}
}
// make the new face
CircularListElement<TMMTriangle>* newFace = m_mesh.AddTriangle();
newFace->GetData().m_edges[0] = e;
newFace->GetData().m_edges[1] = newEdges[0];
newFace->GetData().m_edges[2] = newEdges[1];
MakeCCW(newFace, e, p);
for (int32_t i = 0; i < 2; ++i) {
for (int32_t j = 0; j < 2; ++j) {
if (!newEdges[i]->GetData().m_triangles[j]) {
newEdges[i]->GetData().m_triangles[j] = newFace;
break;
}
}
}
return newFace;
}
bool ICHull::ComputePointVolume(double& totalVolume, bool markVisibleFaces)
{
// mark visible faces
CircularListElement<TMMTriangle>* fHead = m_mesh.GetTriangles().GetHead();
CircularListElement<TMMTriangle>* f = fHead;
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
CircularListElement<TMMVertex>* vertex0 = vertices.GetHead();
bool visible = false;
Vec3<double> pos0 = Vec3<double>(vertex0->GetData().m_pos.X(),
vertex0->GetData().m_pos.Y(),
vertex0->GetData().m_pos.Z());
double vol = 0.0;
totalVolume = 0.0;
Vec3<double> ver0, ver1, ver2;
do {
ver0.X() = f->GetData().m_vertices[0]->GetData().m_pos.X();
ver0.Y() = f->GetData().m_vertices[0]->GetData().m_pos.Y();
ver0.Z() = f->GetData().m_vertices[0]->GetData().m_pos.Z();
ver1.X() = f->GetData().m_vertices[1]->GetData().m_pos.X();
ver1.Y() = f->GetData().m_vertices[1]->GetData().m_pos.Y();
ver1.Z() = f->GetData().m_vertices[1]->GetData().m_pos.Z();
ver2.X() = f->GetData().m_vertices[2]->GetData().m_pos.X();
ver2.Y() = f->GetData().m_vertices[2]->GetData().m_pos.Y();
ver2.Z() = f->GetData().m_vertices[2]->GetData().m_pos.Z();
vol = ComputeVolume4(ver0, ver1, ver2, pos0);
if (vol < -sc_eps) {
vol = fabs(vol);
totalVolume += vol;
if (markVisibleFaces) {
f->GetData().m_visible = true;
m_trianglesToDelete.PushBack(f);
}
visible = true;
}
f = f->GetNext();
} while (f != fHead);
if (m_trianglesToDelete.Size() == m_mesh.m_triangles.GetSize()) {
for (size_t i = 0; i < m_trianglesToDelete.Size(); i++) {
m_trianglesToDelete[i]->GetData().m_visible = false;
}
visible = false;
}
// if no faces visible from p then p is inside the hull
if (!visible && markVisibleFaces) {
vertices.Delete();
m_trianglesToDelete.Resize(0);
return false;
}
return true;
}
bool ICHull::ProcessPoint()
{
double totalVolume = 0.0;
if (!ComputePointVolume(totalVolume, true)) {
return false;
}
// Mark edges in interior of visible region for deletion.
// Create a new face based on each border edge
CircularListElement<TMMVertex>* v0 = m_mesh.GetVertices().GetHead();
CircularListElement<TMMEdge>* eHead = m_mesh.GetEdges().GetHead();
CircularListElement<TMMEdge>* e = eHead;
CircularListElement<TMMEdge>* tmp = 0;
int32_t nvisible = 0;
m_edgesToDelete.Resize(0);
m_edgesToUpdate.Resize(0);
do {
tmp = e->GetNext();
nvisible = 0;
for (int32_t k = 0; k < 2; k++) {
if (e->GetData().m_triangles[k]->GetData().m_visible) {
nvisible++;
}
}
if (nvisible == 2) {
m_edgesToDelete.PushBack(e);
}
else if (nvisible == 1) {
e->GetData().m_newFace = MakeConeFace(e, v0);
m_edgesToUpdate.PushBack(e);
}
e = tmp;
} while (e != eHead);
return true;
}
bool ICHull::MakeCCW(CircularListElement<TMMTriangle>* f,
CircularListElement<TMMEdge>* e,
CircularListElement<TMMVertex>* v)
{
// the visible face adjacent to e
CircularListElement<TMMTriangle>* fv;
if (e->GetData().m_triangles[0]->GetData().m_visible) {
fv = e->GetData().m_triangles[0];
}
else {
fv = e->GetData().m_triangles[1];
}
// set vertex[0] and vertex[1] to have the same orientation as the corresponding vertices of fv.
int32_t i; // index of e->m_vertices[0] in fv
CircularListElement<TMMVertex>* v0 = e->GetData().m_vertices[0];
CircularListElement<TMMVertex>* v1 = e->GetData().m_vertices[1];
for (i = 0; fv->GetData().m_vertices[i] != v0; i++)
;
if (fv->GetData().m_vertices[(i + 1) % 3] != e->GetData().m_vertices[1]) {
f->GetData().m_vertices[0] = v1;
f->GetData().m_vertices[1] = v0;
}
else {
f->GetData().m_vertices[0] = v0;
f->GetData().m_vertices[1] = v1;
// swap edges
CircularListElement<TMMEdge>* tmp = f->GetData().m_edges[0];
f->GetData().m_edges[0] = f->GetData().m_edges[1];
f->GetData().m_edges[1] = tmp;
}
f->GetData().m_vertices[2] = v;
return true;
}
bool ICHull::CleanUp(uint32_t& addedPoints)
{
bool r0 = CleanEdges();
bool r1 = CleanTriangles();
bool r2 = CleanVertices(addedPoints);
return r0 && r1 && r2;
}
bool ICHull::CleanEdges()
{
// integrate the new faces into the data structure
CircularListElement<TMMEdge>* e;
const size_t ne_update = m_edgesToUpdate.Size();
for (size_t i = 0; i < ne_update; ++i) {
e = m_edgesToUpdate[i];
if (e->GetData().m_newFace) {
if (e->GetData().m_triangles[0]->GetData().m_visible) {
e->GetData().m_triangles[0] = e->GetData().m_newFace;
}
else {
e->GetData().m_triangles[1] = e->GetData().m_newFace;
}
e->GetData().m_newFace = 0;
}
}
// delete edges maked for deletion
CircularList<TMMEdge>& edges = m_mesh.GetEdges();
const size_t ne_delete = m_edgesToDelete.Size();
for (size_t i = 0; i < ne_delete; ++i) {
edges.Delete(m_edgesToDelete[i]);
}
m_edgesToDelete.Resize(0);
m_edgesToUpdate.Resize(0);
return true;
}
bool ICHull::CleanTriangles()
{
CircularList<TMMTriangle>& triangles = m_mesh.GetTriangles();
const size_t nt_delete = m_trianglesToDelete.Size();
for (size_t i = 0; i < nt_delete; ++i) {
triangles.Delete(m_trianglesToDelete[i]);
}
m_trianglesToDelete.Resize(0);
return true;
}
bool ICHull::CleanVertices(uint32_t& addedPoints)
{
// mark all vertices incident to some undeleted edge as on the hull
CircularList<TMMEdge>& edges = m_mesh.GetEdges();
CircularListElement<TMMEdge>* e = edges.GetHead();
size_t nE = edges.GetSize();
for (size_t i = 0; i < nE; i++) {
e->GetData().m_vertices[0]->GetData().m_onHull = true;
e->GetData().m_vertices[1]->GetData().m_onHull = true;
e = e->GetNext();
}
// delete all the vertices that have been processed but are not on the hull
CircularList<TMMVertex>& vertices = m_mesh.GetVertices();
CircularListElement<TMMVertex>* vHead = vertices.GetHead();
CircularListElement<TMMVertex>* v = vHead;
v = v->GetPrev();
do {
if (v->GetData().m_tag && !v->GetData().m_onHull) {
CircularListElement<TMMVertex>* tmp = v->GetPrev();
vertices.Delete(v);
v = tmp;
addedPoints--;
}
else {
v->GetData().m_duplicate = 0;
v->GetData().m_onHull = false;
v = v->GetPrev();
}
} while (v->GetData().m_tag && v != vHead);
return true;
}
void ICHull::Clear()
{
m_mesh.Clear();
m_edgesToDelete.Resize(0);
m_edgesToUpdate.Resize(0);
m_trianglesToDelete.Resize(0);
m_isFlat = false;
}
const ICHull& ICHull::operator=(ICHull& rhs)
{
if (&rhs != this) {
m_mesh.Copy(rhs.m_mesh);
m_edgesToDelete = rhs.m_edgesToDelete;
m_edgesToUpdate = rhs.m_edgesToUpdate;
m_trianglesToDelete = rhs.m_trianglesToDelete;
m_isFlat = rhs.m_isFlat;
}
return (*this);
}
bool ICHull::IsInside(const Vec3<double>& pt0, const double eps)
{
const Vec3<double> pt(pt0.X(), pt0.Y(), pt0.Z());
if (m_isFlat) {
size_t nT = m_mesh.m_triangles.GetSize();
Vec3<double> ver0, ver1, ver2, a, b, c;
double u, v;
for (size_t t = 0; t < nT; t++) {
ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X();
ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y();
ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z();
ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X();
ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y();
ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z();
ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X();
ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y();
ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z();
a = ver1 - ver0;
b = ver2 - ver0;
c = pt - ver0;
u = c * a;
v = c * b;
if (u >= 0.0 && u <= 1.0 && v >= 0.0 && u + v <= 1.0) {
return true;
}
m_mesh.m_triangles.Next();
}
return false;
}
else {
size_t nT = m_mesh.m_triangles.GetSize();
Vec3<double> ver0, ver1, ver2;
double vol;
for (size_t t = 0; t < nT; t++) {
ver0.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.X();
ver0.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Y();
ver0.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[0]->GetData().m_pos.Z();
ver1.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.X();
ver1.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Y();
ver1.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[1]->GetData().m_pos.Z();
ver2.X() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.X();
ver2.Y() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Y();
ver2.Z() = m_mesh.m_triangles.GetHead()->GetData().m_vertices[2]->GetData().m_pos.Z();
vol = ComputeVolume4(ver0, ver1, ver2, pt);
if (vol < eps) {
return false;
}
m_mesh.m_triangles.Next();
}
return true;
}
}
}

View File

@@ -0,0 +1,202 @@
/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com)
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "vhacdManifoldMesh.h"
namespace VHACD {
TMMVertex::TMMVertex(void)
{
Initialize();
}
void TMMVertex::Initialize()
{
m_name = 0;
m_id = 0;
m_duplicate = 0;
m_onHull = false;
m_tag = false;
}
TMMVertex::~TMMVertex(void)
{
}
TMMEdge::TMMEdge(void)
{
Initialize();
}
void TMMEdge::Initialize()
{
m_id = 0;
m_triangles[0] = m_triangles[1] = m_newFace = 0;
m_vertices[0] = m_vertices[1] = 0;
}
TMMEdge::~TMMEdge(void)
{
}
void TMMTriangle::Initialize()
{
m_id = 0;
for (int32_t i = 0; i < 3; i++) {
m_edges[i] = 0;
m_vertices[0] = 0;
}
m_visible = false;
}
TMMTriangle::TMMTriangle(void)
{
Initialize();
}
TMMTriangle::~TMMTriangle(void)
{
}
TMMesh::TMMesh()
{
}
TMMesh::~TMMesh(void)
{
}
void TMMesh::GetIFS(Vec3<double>* const points, Vec3<int32_t>* const triangles)
{
size_t nV = m_vertices.GetSize();
size_t nT = m_triangles.GetSize();
for (size_t v = 0; v < nV; v++) {
points[v] = m_vertices.GetData().m_pos;
m_vertices.GetData().m_id = v;
m_vertices.Next();
}
for (size_t f = 0; f < nT; f++) {
TMMTriangle& currentTriangle = m_triangles.GetData();
triangles[f].X() = static_cast<int32_t>(currentTriangle.m_vertices[0]->GetData().m_id);
triangles[f].Y() = static_cast<int32_t>(currentTriangle.m_vertices[1]->GetData().m_id);
triangles[f].Z() = static_cast<int32_t>(currentTriangle.m_vertices[2]->GetData().m_id);
m_triangles.Next();
}
}
void TMMesh::Clear()
{
m_vertices.Clear();
m_edges.Clear();
m_triangles.Clear();
}
void TMMesh::Copy(TMMesh& mesh)
{
Clear();
// updating the id's
size_t nV = mesh.m_vertices.GetSize();
size_t nE = mesh.m_edges.GetSize();
size_t nT = mesh.m_triangles.GetSize();
for (size_t v = 0; v < nV; v++) {
mesh.m_vertices.GetData().m_id = v;
mesh.m_vertices.Next();
}
for (size_t e = 0; e < nE; e++) {
mesh.m_edges.GetData().m_id = e;
mesh.m_edges.Next();
}
for (size_t f = 0; f < nT; f++) {
mesh.m_triangles.GetData().m_id = f;
mesh.m_triangles.Next();
}
// copying data
m_vertices = mesh.m_vertices;
m_edges = mesh.m_edges;
m_triangles = mesh.m_triangles;
// generate mapping
CircularListElement<TMMVertex>** vertexMap = new CircularListElement<TMMVertex>*[nV];
CircularListElement<TMMEdge>** edgeMap = new CircularListElement<TMMEdge>*[nE];
CircularListElement<TMMTriangle>** triangleMap = new CircularListElement<TMMTriangle>*[nT];
for (size_t v = 0; v < nV; v++) {
vertexMap[v] = m_vertices.GetHead();
m_vertices.Next();
}
for (size_t e = 0; e < nE; e++) {
edgeMap[e] = m_edges.GetHead();
m_edges.Next();
}
for (size_t f = 0; f < nT; f++) {
triangleMap[f] = m_triangles.GetHead();
m_triangles.Next();
}
// updating pointers
for (size_t v = 0; v < nV; v++) {
if (vertexMap[v]->GetData().m_duplicate) {
vertexMap[v]->GetData().m_duplicate = edgeMap[vertexMap[v]->GetData().m_duplicate->GetData().m_id];
}
}
for (size_t e = 0; e < nE; e++) {
if (edgeMap[e]->GetData().m_newFace) {
edgeMap[e]->GetData().m_newFace = triangleMap[edgeMap[e]->GetData().m_newFace->GetData().m_id];
}
if (nT > 0) {
for (int32_t f = 0; f < 2; f++) {
if (edgeMap[e]->GetData().m_triangles[f]) {
edgeMap[e]->GetData().m_triangles[f] = triangleMap[edgeMap[e]->GetData().m_triangles[f]->GetData().m_id];
}
}
}
for (int32_t v = 0; v < 2; v++) {
if (edgeMap[e]->GetData().m_vertices[v]) {
edgeMap[e]->GetData().m_vertices[v] = vertexMap[edgeMap[e]->GetData().m_vertices[v]->GetData().m_id];
}
}
}
for (size_t f = 0; f < nT; f++) {
if (nE > 0) {
for (int32_t e = 0; e < 3; e++) {
if (triangleMap[f]->GetData().m_edges[e]) {
triangleMap[f]->GetData().m_edges[e] = edgeMap[triangleMap[f]->GetData().m_edges[e]->GetData().m_id];
}
}
}
for (int32_t v = 0; v < 3; v++) {
if (triangleMap[f]->GetData().m_vertices[v]) {
triangleMap[f]->GetData().m_vertices[v] = vertexMap[triangleMap[f]->GetData().m_vertices[v]->GetData().m_id];
}
}
}
delete[] vertexMap;
delete[] edgeMap;
delete[] triangleMap;
}
bool TMMesh::CheckConsistancy()
{
size_t nE = m_edges.GetSize();
size_t nT = m_triangles.GetSize();
for (size_t e = 0; e < nE; e++) {
for (int32_t f = 0; f < 2; f++) {
if (!m_edges.GetHead()->GetData().m_triangles[f]) {
return false;
}
}
m_edges.Next();
}
for (size_t f = 0; f < nT; f++) {
for (int32_t e = 0; e < 3; e++) {
int32_t found = 0;
for (int32_t k = 0; k < 2; k++) {
if (m_triangles.GetHead()->GetData().m_edges[e]->GetData().m_triangles[k] == m_triangles.GetHead()) {
found++;
}
}
if (found != 1) {
return false;
}
}
m_triangles.Next();
}
return true;
}
}

376
thirdparty/vhacd/src/vhacdMesh.cpp vendored Normal file
View File

@@ -0,0 +1,376 @@
/* Copyright (c) 2011 Khaled Mamou (kmamou at gmail dot com)
All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
3. The names of the contributors may not be used to endorse or promote products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _CRT_SECURE_NO_WARNINGS
#define _CRT_SECURE_NO_WARNINGS
#endif
#include "btConvexHullComputer.h"
#include "vhacdMesh.h"
#include "FloatMath.h"
#include <fstream>
#include <iosfwd>
#include <iostream>
#include <stdio.h>
#include <stdlib.h>
#include <string>
namespace VHACD {
Mesh::Mesh()
{
m_diag = 1.0;
}
Mesh::~Mesh()
{
}
Vec3<double>& Mesh::ComputeCenter(void)
{
const size_t nV = GetNPoints();
if (nV)
{
double center[3];
uint32_t pcount = uint32_t(GetNPoints());
const double *points = GetPoints();
uint32_t tcount = uint32_t(GetNTriangles());
const uint32_t *indices = (const uint32_t *)GetTriangles();
FLOAT_MATH::fm_computeCentroid(pcount, points, tcount, indices, center);
m_center.X() = center[0];
m_center.Y() = center[1];
m_center.Z() = center[2];
m_minBB = GetPoint(0);
m_maxBB = GetPoint(0);
for (size_t v = 1; v < nV; v++)
{
Vec3<double> p = GetPoint(v);
if (p.X() < m_minBB.X())
{
m_minBB.X() = p.X();
}
if (p.Y() < m_minBB.Y())
{
m_minBB.Y() = p.Y();
}
if (p.Z() < m_minBB.Z())
{
m_minBB.Z() = p.Z();
}
if (p.X() > m_maxBB.X())
{
m_maxBB.X() = p.X();
}
if (p.Y() > m_maxBB.Y())
{
m_maxBB.Y() = p.Y();
}
if (p.Z() > m_maxBB.Z())
{
m_maxBB.Z() = p.Z();
}
}
}
return m_center;
}
double Mesh::ComputeVolume() const
{
const size_t nV = GetNPoints();
const size_t nT = GetNTriangles();
if (nV == 0 || nT == 0) {
return 0.0;
}
Vec3<double> bary(0.0, 0.0, 0.0);
for (size_t v = 0; v < nV; v++) {
bary += GetPoint(v);
}
bary /= static_cast<double>(nV);
Vec3<double> ver0, ver1, ver2;
double totalVolume = 0.0;
for (int32_t t = 0; t < int32_t(nT); t++) {
const Vec3<int32_t>& tri = GetTriangle(t);
ver0 = GetPoint(tri[0]);
ver1 = GetPoint(tri[1]);
ver2 = GetPoint(tri[2]);
totalVolume += ComputeVolume4(ver0, ver1, ver2, bary);
}
return totalVolume / 6.0;
}
void Mesh::ComputeConvexHull(const double* const pts,
const size_t nPts)
{
ResizePoints(0);
ResizeTriangles(0);
btConvexHullComputer ch;
ch.compute(pts, 3 * sizeof(double), (int32_t)nPts, -1.0, -1.0);
for (int32_t v = 0; v < ch.vertices.size(); v++) {
AddPoint(Vec3<double>(ch.vertices[v].getX(), ch.vertices[v].getY(), ch.vertices[v].getZ()));
}
const int32_t nt = ch.faces.size();
for (int32_t t = 0; t < nt; ++t) {
const btConvexHullComputer::Edge* sourceEdge = &(ch.edges[ch.faces[t]]);
int32_t a = sourceEdge->getSourceVertex();
int32_t b = sourceEdge->getTargetVertex();
const btConvexHullComputer::Edge* edge = sourceEdge->getNextEdgeOfFace();
int32_t c = edge->getTargetVertex();
while (c != a) {
AddTriangle(Vec3<int32_t>(a, b, c));
edge = edge->getNextEdgeOfFace();
b = c;
c = edge->getTargetVertex();
}
}
}
void Mesh::Clip(const Plane& plane,
SArray<Vec3<double> >& positivePart,
SArray<Vec3<double> >& negativePart) const
{
const size_t nV = GetNPoints();
if (nV == 0) {
return;
}
double d;
for (size_t v = 0; v < nV; v++) {
const Vec3<double>& pt = GetPoint(v);
d = plane.m_a * pt[0] + plane.m_b * pt[1] + plane.m_c * pt[2] + plane.m_d;
if (d > 0.0) {
positivePart.PushBack(pt);
}
else if (d < 0.0) {
negativePart.PushBack(pt);
}
else {
positivePart.PushBack(pt);
negativePart.PushBack(pt);
}
}
}
bool Mesh::IsInside(const Vec3<double>& pt) const
{
const size_t nV = GetNPoints();
const size_t nT = GetNTriangles();
if (nV == 0 || nT == 0) {
return false;
}
Vec3<double> ver0, ver1, ver2;
double volume;
for (int32_t t = 0; t < int32_t(nT); t++) {
const Vec3<int32_t>& tri = GetTriangle(t);
ver0 = GetPoint(tri[0]);
ver1 = GetPoint(tri[1]);
ver2 = GetPoint(tri[2]);
volume = ComputeVolume4(ver0, ver1, ver2, pt);
if (volume < 0.0) {
return false;
}
}
return true;
}
double Mesh::ComputeDiagBB()
{
const size_t nPoints = GetNPoints();
if (nPoints == 0)
return 0.0;
Vec3<double> minBB = m_points[0];
Vec3<double> maxBB = m_points[0];
double x, y, z;
for (size_t v = 1; v < nPoints; v++) {
x = m_points[v][0];
y = m_points[v][1];
z = m_points[v][2];
if (x < minBB[0])
minBB[0] = x;
else if (x > maxBB[0])
maxBB[0] = x;
if (y < minBB[1])
minBB[1] = y;
else if (y > maxBB[1])
maxBB[1] = y;
if (z < minBB[2])
minBB[2] = z;
else if (z > maxBB[2])
maxBB[2] = z;
}
return (m_diag = (maxBB - minBB).GetNorm());
}
#ifdef VHACD_DEBUG_MESH
bool Mesh::SaveVRML2(const std::string& fileName) const
{
std::ofstream fout(fileName.c_str());
if (fout.is_open()) {
const Material material;
if (SaveVRML2(fout, material)) {
fout.close();
return true;
}
return false;
}
return false;
}
bool Mesh::SaveVRML2(std::ofstream& fout, const Material& material) const
{
if (fout.is_open()) {
fout.setf(std::ios::fixed, std::ios::floatfield);
fout.setf(std::ios::showpoint);
fout.precision(6);
size_t nV = m_points.Size();
size_t nT = m_triangles.Size();
fout << "#VRML V2.0 utf8" << std::endl;
fout << "" << std::endl;
fout << "# Vertices: " << nV << std::endl;
fout << "# Triangles: " << nT << std::endl;
fout << "" << std::endl;
fout << "Group {" << std::endl;
fout << " children [" << std::endl;
fout << " Shape {" << std::endl;
fout << " appearance Appearance {" << std::endl;
fout << " material Material {" << std::endl;
fout << " diffuseColor " << material.m_diffuseColor[0] << " "
<< material.m_diffuseColor[1] << " "
<< material.m_diffuseColor[2] << std::endl;
fout << " ambientIntensity " << material.m_ambientIntensity << std::endl;
fout << " specularColor " << material.m_specularColor[0] << " "
<< material.m_specularColor[1] << " "
<< material.m_specularColor[2] << std::endl;
fout << " emissiveColor " << material.m_emissiveColor[0] << " "
<< material.m_emissiveColor[1] << " "
<< material.m_emissiveColor[2] << std::endl;
fout << " shininess " << material.m_shininess << std::endl;
fout << " transparency " << material.m_transparency << std::endl;
fout << " }" << std::endl;
fout << " }" << std::endl;
fout << " geometry IndexedFaceSet {" << std::endl;
fout << " ccw TRUE" << std::endl;
fout << " solid TRUE" << std::endl;
fout << " convex TRUE" << std::endl;
if (nV > 0) {
fout << " coord DEF co Coordinate {" << std::endl;
fout << " point [" << std::endl;
for (size_t v = 0; v < nV; v++) {
fout << " " << m_points[v][0] << " "
<< m_points[v][1] << " "
<< m_points[v][2] << "," << std::endl;
}
fout << " ]" << std::endl;
fout << " }" << std::endl;
}
if (nT > 0) {
fout << " coordIndex [ " << std::endl;
for (size_t f = 0; f < nT; f++) {
fout << " " << m_triangles[f][0] << ", "
<< m_triangles[f][1] << ", "
<< m_triangles[f][2] << ", -1," << std::endl;
}
fout << " ]" << std::endl;
}
fout << " }" << std::endl;
fout << " }" << std::endl;
fout << " ]" << std::endl;
fout << "}" << std::endl;
return true;
}
return false;
}
bool Mesh::SaveOFF(const std::string& fileName) const
{
std::ofstream fout(fileName.c_str());
if (fout.is_open()) {
size_t nV = m_points.Size();
size_t nT = m_triangles.Size();
fout << "OFF" << std::endl;
fout << nV << " " << nT << " " << 0 << std::endl;
for (size_t v = 0; v < nV; v++) {
fout << m_points[v][0] << " "
<< m_points[v][1] << " "
<< m_points[v][2] << std::endl;
}
for (size_t f = 0; f < nT; f++) {
fout << "3 " << m_triangles[f][0] << " "
<< m_triangles[f][1] << " "
<< m_triangles[f][2] << std::endl;
}
fout.close();
return true;
}
return false;
}
bool Mesh::LoadOFF(const std::string& fileName, bool invert)
{
FILE* fid = fopen(fileName.c_str(), "r");
if (fid) {
const std::string strOFF("OFF");
char temp[1024];
fscanf(fid, "%s", temp);
if (std::string(temp) != strOFF) {
fclose(fid);
return false;
}
else {
int32_t nv = 0;
int32_t nf = 0;
int32_t ne = 0;
fscanf(fid, "%i", &nv);
fscanf(fid, "%i", &nf);
fscanf(fid, "%i", &ne);
m_points.Resize(nv);
m_triangles.Resize(nf);
Vec3<double> coord;
float x, y, z;
for (int32_t p = 0; p < nv; p++) {
fscanf(fid, "%f", &x);
fscanf(fid, "%f", &y);
fscanf(fid, "%f", &z);
m_points[p][0] = x;
m_points[p][1] = y;
m_points[p][2] = z;
}
int32_t i, j, k, s;
for (int32_t t = 0; t < nf; ++t) {
fscanf(fid, "%i", &s);
if (s == 3) {
fscanf(fid, "%i", &i);
fscanf(fid, "%i", &j);
fscanf(fid, "%i", &k);
m_triangles[t][0] = i;
if (invert) {
m_triangles[t][1] = k;
m_triangles[t][2] = j;
}
else {
m_triangles[t][1] = j;
m_triangles[t][2] = k;
}
}
else // Fix me: support only triangular meshes
{
for (int32_t h = 0; h < s; ++h)
fscanf(fid, "%i", &s);
}
}
fclose(fid);
}
}
else {
return false;
}
return true;
}
#endif // VHACD_DEBUG_MESH
}

View File

@@ -0,0 +1,208 @@
#include "vhacdRaycastMesh.h"
#include <math.h>
#include <assert.h>
namespace RAYCAST_MESH
{
/* a = b - c */
#define vector(a,b,c) \
(a)[0] = (b)[0] - (c)[0]; \
(a)[1] = (b)[1] - (c)[1]; \
(a)[2] = (b)[2] - (c)[2];
#define innerProduct(v,q) \
((v)[0] * (q)[0] + \
(v)[1] * (q)[1] + \
(v)[2] * (q)[2])
#define crossProduct(a,b,c) \
(a)[0] = (b)[1] * (c)[2] - (c)[1] * (b)[2]; \
(a)[1] = (b)[2] * (c)[0] - (c)[2] * (b)[0]; \
(a)[2] = (b)[0] * (c)[1] - (c)[0] * (b)[1];
static inline bool rayIntersectsTriangle(const double *p,const double *d,const double *v0,const double *v1,const double *v2,double &t)
{
double e1[3],e2[3],h[3],s[3],q[3];
double a,f,u,v;
vector(e1,v1,v0);
vector(e2,v2,v0);
crossProduct(h,d,e2);
a = innerProduct(e1,h);
if (a > -0.00001 && a < 0.00001)
return(false);
f = 1/a;
vector(s,p,v0);
u = f * (innerProduct(s,h));
if (u < 0.0 || u > 1.0)
return(false);
crossProduct(q,s,e1);
v = f * innerProduct(d,q);
if (v < 0.0 || u + v > 1.0)
return(false);
// at this stage we can compute t to find out where
// the intersection point is on the line
t = f * innerProduct(e2,q);
if (t > 0) // ray intersection
return(true);
else // this means that there is a line intersection
// but not a ray intersection
return (false);
}
static double getPointDistance(const double *p1, const double *p2)
{
double dx = p1[0] - p2[0];
double dy = p1[1] - p2[1];
double dz = p1[2] - p2[2];
return sqrt(dx*dx + dy*dy + dz*dz);
}
class MyRaycastMesh : public VHACD::RaycastMesh
{
public:
template <class T>
MyRaycastMesh(uint32_t vcount,
const T *vertices,
uint32_t tcount,
const uint32_t *indices)
{
mVcount = vcount;
mVertices = new double[mVcount * 3];
for (uint32_t i = 0; i < mVcount; i++)
{
mVertices[i * 3 + 0] = vertices[0];
mVertices[i * 3 + 1] = vertices[1];
mVertices[i * 3 + 2] = vertices[2];
vertices += 3;
}
mTcount = tcount;
mIndices = new uint32_t[mTcount * 3];
for (uint32_t i = 0; i < mTcount; i++)
{
mIndices[i * 3 + 0] = indices[0];
mIndices[i * 3 + 1] = indices[1];
mIndices[i * 3 + 2] = indices[2];
indices += 3;
}
}
~MyRaycastMesh(void)
{
delete[]mVertices;
delete[]mIndices;
}
virtual void release(void)
{
delete this;
}
virtual bool raycast(const double *from, // The starting point of the raycast
const double *to, // The ending point of the raycast
const double *closestToPoint, // The point to match the nearest hit location (can just be the 'from' location of no specific point)
double *hitLocation, // The point where the ray hit nearest to the 'closestToPoint' location
double *hitDistance) final // The distance the ray traveled to the hit location
{
bool ret = false;
double dir[3];
dir[0] = to[0] - from[0];
dir[1] = to[1] - from[1];
dir[2] = to[2] - from[2];
double distance = sqrt( dir[0]*dir[0] + dir[1]*dir[1]+dir[2]*dir[2] );
if ( distance < 0.0000000001f ) return false;
double recipDistance = 1.0f / distance;
dir[0]*=recipDistance;
dir[1]*=recipDistance;
dir[2]*=recipDistance;
const uint32_t *indices = mIndices;
const double *vertices = mVertices;
double nearestDistance = distance;
for (uint32_t tri=0; tri<mTcount; tri++)
{
uint32_t i1 = indices[tri*3+0];
uint32_t i2 = indices[tri*3+1];
uint32_t i3 = indices[tri*3+2];
const double *p1 = &vertices[i1*3];
const double *p2 = &vertices[i2*3];
const double *p3 = &vertices[i3*3];
double t;
if ( rayIntersectsTriangle(from,dir,p1,p2,p3,t))
{
double hitPos[3];
hitPos[0] = from[0] + dir[0] * t;
hitPos[1] = from[1] + dir[1] * t;
hitPos[2] = from[2] + dir[2] * t;
double pointDistance = getPointDistance(hitPos, closestToPoint);
if (pointDistance < nearestDistance )
{
nearestDistance = pointDistance;
if ( hitLocation )
{
hitLocation[0] = hitPos[0];
hitLocation[1] = hitPos[1];
hitLocation[2] = hitPos[2];
}
if ( hitDistance )
{
*hitDistance = pointDistance;
}
ret = true;
}
}
}
return ret;
}
uint32_t mVcount;
double *mVertices;
uint32_t mTcount;
uint32_t *mIndices;
};
};
using namespace RAYCAST_MESH;
namespace VHACD
{
RaycastMesh * RaycastMesh::createRaycastMesh(uint32_t vcount, // The number of vertices in the source triangle mesh
const double *vertices, // The array of vertex positions in the format x1,y1,z1..x2,y2,z2.. etc.
uint32_t tcount, // The number of triangles in the source triangle mesh
const uint32_t *indices) // The triangle indices in the format of i1,i2,i3 ... i4,i5,i6, ...
{
MyRaycastMesh *m = new MyRaycastMesh(vcount, vertices, tcount, indices);
return static_cast<RaycastMesh *>(m);
}
RaycastMesh * RaycastMesh::createRaycastMesh(uint32_t vcount, // The number of vertices in the source triangle mesh
const float *vertices, // The array of vertex positions in the format x1,y1,z1..x2,y2,z2.. etc.
uint32_t tcount, // The number of triangles in the source triangle mesh
const uint32_t *indices) // The triangle indices in the format of i1,i2,i3 ... i4,i5,i6, ...
{
MyRaycastMesh *m = new MyRaycastMesh(vcount, vertices, tcount, indices);
return static_cast<RaycastMesh *>(m);
}
} // end of VHACD namespace

1626
thirdparty/vhacd/src/vhacdVolume.cpp vendored Normal file

File diff suppressed because it is too large Load Diff