16 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) 59 template <
typename Real>
71 std::function<
void(
unsigned int)>
const* inProgress);
73 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) 75 std::shared_ptr<GraphicsEngine>
const& inEngine,
76 std::shared_ptr<ProgramFactory>
const& inFactory,
77 std::function<
void(
unsigned int)>
const* inProgress);
80 std::function<void(unsigned int)>
const*
progress;
93 void operator()(
unsigned int numIterations,
bool useSquareTopology,
94 int numVertices,
Vector3<Real> const* vertices,
int numIndices,
98 void TopologicalVertexDistanceTransform();
99 void AssignBoundaryTextureCoordinatesSquare();
100 void AssignBoundaryTextureCoordinatesDisk();
101 void ComputeMeanValueWeights();
102 void SolveSystem(
unsigned int numIterations);
103 void SolveSystemCPUSingle(
unsigned int numIterations);
104 void SolveSystemCPUMultiple(
unsigned int numIterations);
118 enum { INTERIOR_VERTEX = -1 };
136 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) && defined(GTE_DEV_OPENGL) 153 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) 155 void SolveSystemGPU(
unsigned int numIterations);
156 std::shared_ptr<ComputeProgram> mSolveSystem;
157 std::shared_ptr<ConstantBuffer> mBoundBuffer;
158 std::shared_ptr<StructuredBuffer> mVGBuffer;
159 std::shared_ptr<StructuredBuffer> mVGDBuffer;
160 std::shared_ptr<StructuredBuffer> mOVBuffer;
161 std::shared_ptr<StructuredBuffer> mTCoordsBuffer[2];
166 template <
typename Real>
171 template <
typename Real>
178 template <
typename Real>
180 std::function<
void(
unsigned int)>
const* inProgress)
187 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) 189 template <
typename Real>
191 std::shared_ptr<GraphicsEngine>
const& inEngine,
192 std::shared_ptr<ProgramFactory>
const& inFactory,
193 std::function<
void(
unsigned int)>
const* inProgress)
202 template <
typename Real>
214 template <
typename Real>
216 bool useSquareTopology,
int numVertices,
Vector3<Real> const* vertices,
221 if (numIterations & 1)
233 for (
int i = 0; i < numVertices; ++i)
241 int const numTriangles = numIndices / 3;
242 for (
int t = 0;
t < numTriangles; ++
t)
252 if (useSquareTopology)
265 template <
typename Real>
273 std::pair<int, Real> initialData = std::make_pair(-1, (Real)-1);
288 std::fill(numAdjacencies.begin(), numAdjacencies.end(), 0);
292 ++numAdjacencies[element.first.V[0]];
293 ++numAdjacencies[element.first.V[1]];
295 if (element.second->T[1].lock())
305 int v0 = element.second->V[0],
v1 = element.second->V[1];
306 auto tri = element.second->T[0].lock();
308 for (i = 0; i < 3; ++i)
311 if (v2 != v0 && v2 !=
v1)
314 v0 = tri->V[(i + 1) % 3];
315 v1 = tri->V[(i + 2) % 3];
325 for (
int vIndex = 0, aIndex = 0; vIndex <
mNumVertices; ++vIndex)
327 int numAdjacent = numAdjacencies[vIndex];
328 mVertexGraph[vIndex].range = { { aIndex, numAdjacent } };
329 aIndex += numAdjacent;
331 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) && defined(GTE_DEV_OPENGL) 338 std::set<int> currFront;
341 int v0 = element.second->V[0],
v1 = element.second->V[1];
342 for (
int i = 0; i < 2; ++i)
351 currFront.insert(v0);
356 for (
int j = 0; j < range[1]; ++j)
359 if (data.second == (Real)-1)
362 data.second = (Real)0;
372 int currDistance = 0, nextDistance = 1;
373 size_t numFrontVertices = currFront.size();
375 while (currFront.size() > 0)
377 std::set<int> nextFront;
378 for (
auto v : currFront)
382 for (
int j = 0; j < range[1]; ++j, ++current)
384 int a = current->first;
392 std::copy(nextFront.begin(), nextFront.end(),
mOrderedVertices.begin() + numFrontVertices);
393 numFrontVertices += nextFront.size();
394 currFront = std::move(nextFront);
395 currDistance = nextDistance++;
399 template <
typename Real>
410 Real total = (Real)0;
420 Real invTotal = ((Real)1) / total;
421 for (
auto& d : distance)
426 auto begin = distance.begin(),
end = distance.end();
427 int endYMin = (
int)(std::lower_bound(begin,
end, (Real)0.25) - begin);
428 int endXMax = (
int)(std::lower_bound(begin,
end, (Real)0.50) - begin);
429 int endYMax = (
int)(std::lower_bound(begin,
end, (Real)0.75) - begin);
430 int endXMin = (
int)distance.size() - 1;
437 for (i = 0; i < endYMin; ++i)
449 for (++i; i < endXMax; ++i)
453 mTCoords[
v1][1] = distance[i] * (Real)4 - (Real)1;
461 for (++i; i < endYMax; ++i)
464 mTCoords[
v1][0] = (Real)3 - distance[i] * (Real)4;
473 for (++i; i < endXMin; ++i)
477 mTCoords[
v1][1] = (Real)4 - distance[i] * (Real)4;
482 template <
typename Real>
492 Real total = (Real)0;
515 Real
angle = multiplier * distance[i - 1];
516 mTCoords[
v1][0] = (cos(angle) + (Real)1) * (Real)0.5;
517 mTCoords[
v1][1] = (sin(angle) + (Real)1) * (Real)0.5;
522 template <
typename Real>
527 int v0 = edge->V[0],
v1 = edge->V[1];
528 for (
int i = 0; i < 2; ++i)
537 if (x1mx0length >(Real)0)
541 for (
int j = 0; j < 2; ++j)
544 auto tri = edge->T[j].lock();
546 for (k = 0; k < 3; ++k)
549 if (v2 != v0 && v2 !=
v1)
554 if (x2mx0Length >(Real)0)
556 Real dot =
Dot(X2mX0, X1mX0);
557 Real cs = std::min(std::max(dot, (Real)-1), (Real)1);
558 Real
angle = acos(cs);
559 weight += tan(angle * (Real)0.5);
569 weight /= x1mx0length;
577 for (
int j = 0; j < range[1]; ++j)
580 if (data.first ==
v1)
591 template <
typename Real>
604 Real
weight, weightSum = zero;
605 for (
int j = 0; j < range[1]; ++j, ++current)
607 int v1 = current->first;
610 weight = current->second;
619 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) 622 SolveSystemGPU(numIterations);
638 template <
typename Real>
651 for (
unsigned int i = 1; i <= numIterations; ++i)
664 Real
weight, weightSum = (Real)0;
665 for (
int k = 0; k < range[1]; ++k, ++current)
667 int v1 = current->first;
668 weight = current->second;
670 tcoord += weight * inTCoords[
v1];
673 outTCoords[
v0] = tcoord;
676 std::swap(inTCoords, outTCoords);
680 template <
typename Real>
692 int numVPerThread = numV /
mCModel->numThreads;
693 std::vector<int> vmin(
mCModel->numThreads), vmax(
mCModel->numThreads);
694 for (
unsigned int t = 0;
t <
mCModel->numThreads; ++
t)
696 vmin[
t] = mNumBoundaryEdges +
t * numVPerThread;
697 vmax[
t] = vmin[
t] + numVPerThread - 1;
704 for (
unsigned int i = 1; i <= numIterations; ++i)
712 std::vector<std::thread> process(
mCModel->numThreads);
713 for (
unsigned int t = 0;
t <
mCModel->numThreads; ++
t)
715 process[
t] = std::thread([
this,
t, &vmin, &vmax, inTCoords,
718 for (
int j = vmin[
t]; j <= vmax[
t]; ++j)
724 Real
weight, weightSum = (Real)0;
725 for (
int k = 0; k < range[1]; ++k, ++current)
727 int v1 = current->first;
728 weight = current->second;
730 tcoord += weight * inTCoords[
v1];
733 outTCoords[
v0] = tcoord;
739 for (
unsigned int t = 0;
t <
mCModel->numThreads; ++
t)
744 std::swap(inTCoords, outTCoords);
748 #if defined(GTE_COMPUTE_MODEL_ALLOW_GPGPU) 750 template <
typename Real>
753 mCModel->factory->defines.Set(
"NUM_X_THREADS", 8);
754 mCModel->factory->defines.Set(
"NUM_Y_THREADS", 8);
755 if (std::numeric_limits<Real>::max() == std::numeric_limits<float>::max())
757 mCModel->factory->defines.Set(
"Real",
"float");
758 #if defined(GTE_DEV_OPENGL) 759 mCModel->factory->defines.Set(
"Real2",
"vec2");
761 mCModel->factory->defines.Set(
"Real2",
"float2");
766 mCModel->factory->defines.Set(
"Real",
"double");
767 #if defined(GTE_DEV_OPENGL) 768 mCModel->factory->defines.Set(
"Real2",
"dvec2");
770 mCModel->factory->defines.Set(
"Real2",
"double2");
775 int api =
mCModel->factory->GetAPI();
777 std::shared_ptr<ComputeShader> cshader = mSolveSystem->GetCShader();
781 Real factor0 = ceil(sqrt((Real)numInputs));
782 Real factor1 = ceil((Real)numInputs / factor0);
783 int xElements =
static_cast<int>(factor0);
784 int yElements =
static_cast<int>(factor1);
785 int xRem = (xElements % 8);
788 xElements += 8 - xRem;
790 int yRem = (yElements % 8);
793 yElements += 8 - yRem;
795 unsigned int numXGroups = xElements / 8;
796 unsigned int numYGroups = yElements / 8;
798 mBoundBuffer = std::make_shared<ConstantBuffer>(4 *
sizeof(
int),
false);
799 int*
data = mBoundBuffer->Get<
int>();
804 cshader->Set(
"Bounds", mBoundBuffer);
806 unsigned int const vgSize =
static_cast<unsigned int>(
mVertexGraph.size());
807 mVGBuffer = std::make_shared<StructuredBuffer>(vgSize,
sizeof(
Vertex));
809 cshader->Set(
"vertexGraph", mVGBuffer);
811 unsigned int const vgdSize =
static_cast<unsigned int>(
mVertexGraphData.size());
812 mVGDBuffer = std::make_shared<StructuredBuffer>(vgdSize,
sizeof(std::pair<int, Real>));
814 cshader->Set(
"vertexGraphData", mVGDBuffer);
816 unsigned int const ovSize =
static_cast<unsigned int>(
mOrderedVertices.size());
817 mOVBuffer = std::make_shared<StructuredBuffer>(ovSize,
sizeof(
int));
819 cshader->Set(
"orderedVertices", mOVBuffer);
821 for (
int j = 0; j < 2; ++j)
824 mTCoordsBuffer[j]->SetUsage(Resource::SHADER_OUTPUT);
825 Memcpy(mTCoordsBuffer[j]->GetData(),
mTCoords, mTCoordsBuffer[j]->GetNumBytes());
832 for (
unsigned int i = 1; i <= numIterations; ++i)
839 cshader->Set(
"inTCoords", mTCoordsBuffer[0]);
840 cshader->Set(
"outTCoords", mTCoordsBuffer[1]);
841 mCModel->engine->Execute(mSolveSystem, numXGroups, numYGroups, 1);
842 std::swap(mTCoordsBuffer[0], mTCoordsBuffer[1]);
845 mCModel->engine->CopyGpuToCpu(mTCoordsBuffer[0]);
846 Memcpy(
mTCoords, mTCoordsBuffer[0]->GetData(), mTCoordsBuffer[0]->GetNumBytes());
void AssignBoundaryTextureCoordinatesSquare()
static std::string const msHLSLSource
EMap const & GetEdges() const
std::vector< int > mVertexInfo
std::set< std::shared_ptr< Edge > > mInteriorEdges
std::vector< int > mOrderedVertices
static std::string const * msSource[]
void SolveSystem(unsigned int numIterations)
std::vector< std::pair< int, Real > > mVertexGraphData
std::function< void(unsigned int)> const * progress
std::array< int, 2 > range
GLuint GLuint GLfloat weight
GLsizei GLsizei GLfloat distance
Vector3< Real > const * mVertices
ETManifoldMesh::Edge Edge
void SolveSystemCPUMultiple(unsigned int numIterations)
GLboolean GLboolean GLboolean GLboolean a
void operator()(unsigned int numIterations, bool useSquareTopology, int numVertices, Vector3< Real > const *vertices, int numIndices, int const *indices, Vector2< Real > *tcoords)
GenerateMeshUV(std::shared_ptr< UVComputeModel > const &cmodel)
void ComputeMeanValueWeights()
GLsizei const GLchar *const * string
GLsizei GLenum const void * indices
typedef int(WINAPI *PFNWGLRELEASEPBUFFERDCARBPROC)(HPBUFFERARB hPbuffer
void AssignBoundaryTextureCoordinatesDisk()
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
virtual std::shared_ptr< Triangle > Insert(int v0, int v1, int v2)
Real Normalize(GVector< Real > &v, bool robust=false)
std::shared_ptr< UVComputeModel > mCModel
static std::string const msGLSLSource
DualQuaternion< Real > Length(DualQuaternion< Real > const &d, bool robust=false)
virtual ~UVComputeModel()
GLfloat GLfloat GLfloat v2
std::vector< Vertex > mVertexGraph
void Memcpy(void *target, void const *source, size_t count)
void SolveSystemCPUSingle(unsigned int numIterations)
void TopologicalVertexDistanceTransform()
Vector2< Real > * mTCoords