00001 #include <stdio.h>
00002 #include <stdlib.h>
00003 #include <string.h>
00004 #include <assert.h>
00005
00062 #include <algorithm>
00063 #include <vector>
00064
00065 #include "ConvexDecomposition.h"
00066 #include "cd_vector.h"
00067 #include "cd_hull.h"
00068 #include "bestfit.h"
00069 #include "planetri.h"
00070 #include "vlookup.h"
00071 #include "splitplane.h"
00072 #include "meshvolume.h"
00073 #include "concavity.h"
00074 #include "bestfitobb.h"
00075 #include "fitsphere.h"
00076 #include "triangulate.h"
00077 #include "float_math.h"
00078
00079 #define MAKE_MESH 1
00080 #define CLOSE_FACE 0
00081
00082 static unsigned int MAXDEPTH=8;
00083 static double CONCAVE_PERCENT=1.0f;
00084 static double MERGE_PERCENT=2.0f;
00085
00086
00087 using namespace ConvexDecomposition;
00088
00089 typedef std::vector< unsigned int > UintVector;
00090
00091 namespace ConvexDecomposition
00092 {
00093
00094 class Edge
00095 {
00096 public:
00097
00098 Edge(unsigned int i1,unsigned int i2)
00099 {
00100 mE1 = i1;
00101 mE2 = i2;
00102 mUsed = false;
00103 }
00104
00105 unsigned int mE1;
00106 unsigned int mE2;
00107 bool mUsed;
00108 };
00109
00110 typedef std::vector< Edge > EdgeVector;
00111
00112 class FaceTri
00113 {
00114 public:
00115 FaceTri(void) { };
00116
00117 FaceTri(const double *vertices,unsigned int i1,unsigned int i2,unsigned int i3)
00118 {
00119 mP1.Set( &vertices[i1*3] );
00120 mP2.Set( &vertices[i2*3] );
00121 mP3.Set( &vertices[i3*3] );
00122 }
00123
00124 Vector3d<double> mP1;
00125 Vector3d<double> mP2;
00126 Vector3d<double> mP3;
00127 Vector3d<double> mNormal;
00128
00129 };
00130
00131
00132
00133 class CHull
00134 {
00135 public:
00136 CHull(const ConvexResult &result)
00137 {
00138 mResult = new ConvexResult(result);
00139 mVolume = computeMeshVolume( result.mHullVertices, result.mHullTcount, result.mHullIndices );
00140
00141 mDiagonal = getBoundingRegion( result.mHullVcount, result.mHullVertices, sizeof(double)*3, mMin, mMax );
00142
00143 double dx = mMax[0] - mMin[0];
00144 double dy = mMax[1] - mMin[1];
00145 double dz = mMax[2] - mMin[2];
00146
00147 dx*=0.1f;
00148 dy*=0.1f;
00149 dz*=0.1f;
00150
00151 mMin[0]-=dx;
00152 mMin[1]-=dy;
00153 mMin[2]-=dz;
00154
00155 mMax[0]+=dx;
00156 mMax[1]+=dy;
00157 mMax[2]+=dz;
00158
00159
00160 }
00161
00162 ~CHull(void)
00163 {
00164 delete mResult;
00165 }
00166
00167 bool overlap(const CHull &h) const
00168 {
00169 return overlapAABB(mMin,mMax, h.mMin, h.mMax );
00170 }
00171
00172 double mMin[3];
00173 double mMax[3];
00174 double mVolume;
00175 double mDiagonal;
00176 ConvexResult *mResult;
00177 };
00178
00179
00180 class CHullSort
00181 {
00182 public:
00183
00184 bool operator()(const CHull *a,const CHull *b) const
00185 {
00186 return a->mVolume < b->mVolume;
00187 }
00188 };
00189
00190
00191 typedef std::vector< CHull * > CHullVector;
00192
00193
00194 class ConvexBuilder : public ConvexDecompInterface
00195 {
00196 public:
00197 ConvexBuilder(ConvexDecompInterface *callback)
00198 {
00199 mCallback = callback;
00200 };
00201
00202 ~ConvexBuilder(void)
00203 {
00204 CHullVector::iterator i;
00205 for (i=mChulls.begin(); i!=mChulls.end(); ++i)
00206 {
00207 CHull *cr = (*i);
00208 delete cr;
00209 }
00210 }
00211
00212 bool isDuplicate(unsigned int i1,unsigned int i2,unsigned int i3,
00213 unsigned int ci1,unsigned int ci2,unsigned int ci3)
00214 {
00215 unsigned int dcount = 0;
00216
00217 assert( i1 != i2 && i1 != i3 && i2 != i3 );
00218 assert( ci1 != ci2 && ci1 != ci3 && ci2 != ci3 );
00219
00220 if ( i1 == ci1 || i1 == ci2 || i1 == ci3 ) dcount++;
00221 if ( i2 == ci1 || i2 == ci2 || i2 == ci3 ) dcount++;
00222 if ( i3 == ci1 || i3 == ci2 || i3 == ci3 ) dcount++;
00223
00224 return dcount == 3;
00225 }
00226
00227 void getMesh(const ConvexResult &cr,VertexLookup vc)
00228 {
00229 unsigned int *src = cr.mHullIndices;
00230
00231 for (unsigned int i=0; i<cr.mHullTcount; i++)
00232 {
00233 unsigned int i1 = *src++;
00234 unsigned int i2 = *src++;
00235 unsigned int i3 = *src++;
00236
00237 const double *p1 = &cr.mHullVertices[i1*3];
00238 const double *p2 = &cr.mHullVertices[i2*3];
00239 const double *p3 = &cr.mHullVertices[i3*3];
00240
00241 i1 = Vl_getIndex(vc,p1);
00242 i2 = Vl_getIndex(vc,p2);
00243 i3 = Vl_getIndex(vc,p3);
00244
00245
00246 }
00247 }
00248
00249 CHull * canMerge(CHull *a,CHull *b)
00250 {
00251
00252 if ( !a->overlap(*b) ) return 0;
00253
00254 if ( MERGE_PERCENT < 0 ) return 0;
00255
00256 assert( a->mVolume > 0 );
00257 assert( b->mVolume > 0 );
00258
00259 CHull *ret = 0;
00260
00261
00262
00263
00264 VertexLookup vc = Vl_createVertexLookup();
00265
00266 getMesh( *a->mResult, vc);
00267 getMesh( *b->mResult, vc);
00268
00269 unsigned int vcount = Vl_getVcount(vc);
00270 const double *vertices = Vl_getVertices(vc);
00271
00272 HullResult hresult;
00273 HullLibrary hl;
00274 HullDesc desc;
00275
00276 desc.SetHullFlag(QF_TRIANGLES);
00277
00278 desc.mVcount = vcount;
00279 desc.mVertices = vertices;
00280 desc.mVertexStride = sizeof(double)*3;
00281
00282 HullError hret = hl.CreateConvexHull(desc,hresult);
00283
00284 if ( hret == QE_OK )
00285 {
00286
00287 double combineVolume = computeMeshVolume( hresult.mOutputVertices, hresult.mNumFaces, hresult.mIndices );
00288 double sumVolume = a->mVolume + b->mVolume;
00289
00290 double percent = (sumVolume*100) / combineVolume;
00291
00292 if ( percent >= (100.0f-MERGE_PERCENT) )
00293 {
00294 ConvexResult cr(hresult.mNumOutputVertices, hresult.mOutputVertices, hresult.mNumFaces, hresult.mIndices);
00295 ret = new CHull(cr);
00296 }
00297 }
00298
00299
00300 Vl_releaseVertexLookup(vc);
00301
00302 return ret;
00303 }
00304
00305 bool combineHulls(void)
00306 {
00307
00308 bool combine = false;
00309
00310 sortChulls(mChulls);
00311
00312 CHullVector output;
00313
00314
00315 CHullVector::iterator i;
00316
00317 for (i=mChulls.begin(); i!=mChulls.end() && !combine; ++i)
00318 {
00319 CHull *cr = (*i);
00320
00321 CHullVector::iterator j;
00322 for (j=mChulls.begin(); j!=mChulls.end(); ++j)
00323 {
00324 CHull *match = (*j);
00325
00326 if ( cr != match )
00327 {
00328
00329 CHull *merge = canMerge(cr,match);
00330
00331 if ( merge )
00332 {
00333
00334 output.push_back(merge);
00335
00336
00337 ++i;
00338 while ( i != mChulls.end() )
00339 {
00340 CHull *cr = (*i);
00341 if ( cr != match )
00342 {
00343 output.push_back(cr);
00344 }
00345 i++;
00346 }
00347
00348 delete cr;
00349 delete match;
00350 combine = true;
00351 break;
00352 }
00353 }
00354 }
00355
00356 if ( combine )
00357 {
00358 break;
00359 }
00360 else
00361 {
00362 output.push_back(cr);
00363 }
00364
00365 }
00366
00367 if ( combine )
00368 {
00369 mChulls.clear();
00370 mChulls = output;
00371 output.clear();
00372 }
00373
00374
00375 return combine;
00376 }
00377
00378 unsigned int process(const DecompDesc &desc)
00379 {
00380
00381 unsigned int ret = 0;
00382
00383 MAXDEPTH = desc.mDepth;
00384 CONCAVE_PERCENT = desc.mCpercent;
00385 MERGE_PERCENT = desc.mPpercent;
00386
00387
00388 doConvexDecomposition(desc.mVcount, desc.mVertices, desc.mTcount, desc.mIndices,this,0,0);
00389
00390
00391 while ( combineHulls() );
00392
00393 CHullVector::iterator i;
00394 for (i=mChulls.begin(); i!=mChulls.end(); ++i)
00395 {
00396 CHull *cr = (*i);
00397
00398
00399
00400
00401 const ConvexResult &c = *cr->mResult;
00402
00403 HullResult result;
00404 HullLibrary hl;
00405 HullDesc hdesc;
00406
00407 hdesc.SetHullFlag(QF_TRIANGLES);
00408
00409 hdesc.mVcount = c.mHullVcount;
00410 hdesc.mVertices = c.mHullVertices;
00411 hdesc.mVertexStride = sizeof(double)*3;
00412 hdesc.mMaxVertices = desc.mMaxVertices;
00413
00414 if ( desc.mSkinWidth > 0 )
00415 {
00416 hdesc.mSkinWidth = desc.mSkinWidth;
00417 hdesc.SetHullFlag(QF_SKIN_WIDTH);
00418 }
00419
00420 HullError ret = hl.CreateConvexHull(hdesc,result);
00421
00422 if ( ret == QE_OK )
00423 {
00424 ConvexResult r(result.mNumOutputVertices, result.mOutputVertices, result.mNumFaces, result.mIndices);
00425
00426 r.mHullVolume = computeMeshVolume( result.mOutputVertices, result.mNumFaces, result.mIndices );
00427
00428 mCallback->ConvexDecompResult(r);
00429 }
00430
00431
00432 delete cr;
00433 }
00434
00435 ret = mChulls.size();
00436
00437 mChulls.clear();
00438
00439 return ret;
00440 }
00441
00442
00443 virtual void ConvexDebugTri(const double *p1,const double *p2,const double *p3,unsigned int color)
00444 {
00445 mCallback->ConvexDebugTri(p1,p2,p3,color);
00446 }
00447
00448 virtual void ConvexDebugOBB(const double *sides, const double *matrix,unsigned int color)
00449 {
00450 mCallback->ConvexDebugOBB(sides,matrix,color);
00451 }
00452 virtual void ConvexDebugPoint(const double *p,double dist,unsigned int color)
00453 {
00454 mCallback->ConvexDebugPoint(p,dist,color);
00455 }
00456
00457 virtual void ConvexDebugBound(const double *bmin,const double *bmax,unsigned int color)
00458 {
00459 mCallback->ConvexDebugBound(bmin,bmax,color);
00460 }
00461
00462 virtual void ConvexDecompResult(ConvexResult &result)
00463 {
00464 CHull *ch = new CHull(result);
00465 mChulls.push_back(ch);
00466 }
00467
00468 void sortChulls(CHullVector &hulls)
00469 {
00470 std::sort( hulls.begin(), hulls.end(), CHullSort() );
00471 }
00472
00473 #define EPSILON 0.001f
00474
00475 bool isEdge(const Vector3d<double> &p,const double *plane)
00476 {
00477 bool ret = false;
00478
00479 double dist = fabs(fm_distToPlane(plane,p.Ptr()));
00480
00481 if ( dist < EPSILON )
00482 {
00483 ret = true;
00484 }
00485
00486
00487 return ret;
00488 }
00489
00490 void addEdge(const Vector3d<double> &p1,const Vector3d<double> &p2,EdgeVector &edges,VertexLookup split,const double *plane)
00491 {
00492 if ( isEdge(p1,plane) && isEdge(p2,plane) )
00493 {
00494 unsigned int i1 = Vl_getIndex(split,p1.Ptr());
00495 unsigned int i2 = Vl_getIndex(split,p2.Ptr());
00496
00497 bool found = false;
00498
00499 for (unsigned int i=0; i<edges.size(); i++)
00500 {
00501 Edge &e = edges[i];
00502 if ( e.mE1 == i1 && e.mE2 == i2 )
00503 {
00504 found = true;
00505 break;
00506 }
00507 if ( e.mE1 == i2 && e.mE2 == i1 )
00508 {
00509 found = true;
00510 break;
00511 }
00512 }
00513 if ( !found )
00514 {
00515 Edge e(i1,i2);
00516 edges.push_back(e);
00517 }
00518 }
00519 }
00520
00521 bool addTri(VertexLookup vl,
00522 UintVector &list,
00523 const Vector3d<double> &p1,
00524 const Vector3d<double> &p2,
00525 const Vector3d<double> &p3,
00526 EdgeVector &edges,
00527 VertexLookup split,
00528 const double *plane)
00529 {
00530 bool ret = false;
00531
00532 unsigned int i1 = Vl_getIndex(vl, p1.Ptr() );
00533 unsigned int i2 = Vl_getIndex(vl, p2.Ptr() );
00534 unsigned int i3 = Vl_getIndex(vl, p3.Ptr() );
00535
00536
00537
00538 if ( i1 != i2 && i1 != i3 && i2 != i3 )
00539 {
00540
00541 list.push_back(i1);
00542 list.push_back(i2);
00543 list.push_back(i3);
00544 #if CLOSE_FACE
00545 addEdge(p1,p2,edges,split,plane);
00546 addEdge(p2,p3,edges,split,plane);
00547 addEdge(p3,p1,edges,split,plane);
00548 #endif
00549 ret = true;
00550 }
00551 return ret;
00552 }
00553
00554 void saveEdges(VertexLookup vl,const EdgeVector &edges,bool front)
00555 {
00556 char scratch[512];
00557 if ( front )
00558 {
00559 static int fcount=1;
00560 sprintf(scratch,"CD_Front%d.obj", fcount++);
00561 }
00562 else
00563 {
00564 static int bcount=1;
00565 sprintf(scratch,"CD_Back%d.obj", bcount++);
00566 }
00567
00568 FILE *fph = fopen(scratch,"wb");
00569 if (fph)
00570 {
00571 unsigned int vcount = Vl_getVcount(vl);
00572 const double *vertices = Vl_getVertices(vl);
00573 fprintf(fph,"v 10 10 0\r\n");
00574 for (unsigned int i=0; i<vcount; i++)
00575 {
00576 fprintf(fph,"v %0.9f %0.9f %0.9f\r\n", vertices[0], vertices[1], vertices[2] );
00577 vertices+=3;
00578 }
00579 for (unsigned int i=0; i<edges.size(); i++)
00580 {
00581 const Edge &e = edges[i];
00582 fprintf(fph,"f %d %d %d\r\n", e.mE1+2, 1, e.mE2+2);
00583 }
00584 fclose(fph);
00585 }
00586
00587 }
00588
00589 void saveObj(VertexLookup vl,const UintVector &indices,bool front)
00590 {
00591 char scratch[512];
00592 if ( front )
00593 {
00594 static int fcount=1;
00595 sprintf(scratch,"CD_Front%d.obj", fcount++);
00596 }
00597 else
00598 {
00599 static int bcount=1;
00600 sprintf(scratch,"CD_Back%d.obj", bcount++);
00601 }
00602
00603 FILE *fph = fopen(scratch,"wb");
00604 if (fph)
00605 {
00606 unsigned int vcount = Vl_getVcount(vl);
00607 const double *vertices = Vl_getVertices(vl);
00608 for (unsigned int i=0; i<vcount; i++)
00609 {
00610 fprintf(fph,"v %0.9f %0.9f %0.9f\r\n", vertices[0], vertices[1], vertices[2] );
00611 vertices+=3;
00612 }
00613 for (unsigned int i=0; i<indices.size()/3; i++)
00614 {
00615 unsigned int i1 = indices[i*3+0];
00616 unsigned int i2 = indices[i*3+1];
00617 unsigned int i3 = indices[i*3+2];
00618 fprintf(fph,"f %d %d %d\r\n", i1+1, i2+1, i3+1);
00619 }
00620 fclose(fph);
00621 }
00622
00623 };
00624
00625 void doConvexDecomposition(unsigned int vcount,
00626 const double *vertices,
00627 unsigned int tcount,
00628 const unsigned int *indices,
00629 ConvexDecompInterface *callback,
00630 double masterVolume,
00631 unsigned int depth)
00632
00633 {
00634
00635 double plane[4];
00636
00637 bool split = false;
00638
00639
00640 if ( depth < MAXDEPTH )
00641 {
00642 if ( CONCAVE_PERCENT >= 0 )
00643 {
00644 double volume;
00645
00646 double c = computeConcavity( vcount, vertices, tcount, indices, callback, plane, volume );
00647
00648 if ( depth == 0 )
00649 {
00650 masterVolume = volume;
00651 }
00652
00653 double percent = (c*100.0f)/masterVolume;
00654
00655 if ( percent > CONCAVE_PERCENT )
00656 {
00657 split = true;
00658 }
00659 }
00660 else
00661 {
00662 split = computeSplitPlane(vcount,vertices,tcount,indices,callback,plane);
00663 }
00664
00665 }
00666
00667 if ( depth >= MAXDEPTH || !split )
00668 {
00669
00670 HullResult result;
00671 HullLibrary hl;
00672 HullDesc desc;
00673
00674 desc.SetHullFlag(QF_TRIANGLES);
00675
00676 desc.mVcount = vcount;
00677 desc.mVertices = vertices;
00678 desc.mVertexStride = sizeof(double)*3;
00679
00680 HullError ret = hl.CreateConvexHull(desc,result);
00681
00682 if ( ret == QE_OK )
00683 {
00684
00685 ConvexResult r(result.mNumOutputVertices, result.mOutputVertices, result.mNumFaces, result.mIndices);
00686
00687
00688 callback->ConvexDecompResult(r);
00689 }
00690
00691
00692 return;
00693 }
00694
00695 UintVector ifront;
00696 UintVector iback;
00697
00698 EdgeVector frontEdges;
00699 EdgeVector backEdges;
00700
00701 VertexLookup vfront = Vl_createVertexLookup();
00702 VertexLookup vback = Vl_createVertexLookup();
00703
00704 VertexLookup splitFront = Vl_createVertexLookup();
00705 VertexLookup splitBack = Vl_createVertexLookup();
00706
00707
00708
00709 if ( 1 )
00710 {
00711
00712
00713
00714 const unsigned int *source = indices;
00715
00716 for (unsigned int i=0; i<tcount; i++)
00717 {
00718 unsigned int i1 = *source++;
00719 unsigned int i2 = *source++;
00720 unsigned int i3 = *source++;
00721
00722 FaceTri t(vertices, i1, i2, i3 );
00723
00724 Vector3d<double> front[4];
00725 Vector3d<double> back[4];
00726
00727 unsigned int fcount=0;
00728 unsigned int bcount=0;
00729
00730 PlaneTriResult result;
00731
00732 result = planeTriIntersection(plane,t.mP1.Ptr(),sizeof(Vector3d<double>),0.00001f,front[0].Ptr(),fcount,back[0].Ptr(),bcount );
00733
00734 if( fcount > 4 || bcount > 4 )
00735 {
00736 result = planeTriIntersection(plane,t.mP1.Ptr(),sizeof(Vector3d<double>),0.00001f,front[0].Ptr(),fcount,back[0].Ptr(),bcount );
00737 }
00738
00739 switch ( result )
00740 {
00741 case PTR_FRONT:
00742
00743 assert( fcount == 3 );
00744
00745 #if MAKE_MESH
00746 addTri( vfront, ifront, front[0], front[1], front[2], frontEdges, splitFront, plane );
00747 #endif
00748
00749 break;
00750 case PTR_BACK:
00751 assert( bcount == 3 );
00752
00753 #if MAKE_MESH
00754 addTri( vback, iback, back[0], back[1], back[2], backEdges, splitBack, plane );
00755 #endif
00756
00757 break;
00758 case PTR_SPLIT:
00759
00760 if ( fcount >= 3 && fcount <= 4)
00761 if ( bcount >= 3 && bcount <= 4)
00762 {
00763 #if MAKE_MESH
00764 addTri( vfront, ifront, front[0], front[1], front[2], frontEdges, splitFront, plane );
00765 addTri( vback, iback, back[0], back[1], back[2], backEdges, splitBack, plane );
00766
00767 if ( fcount == 4 )
00768 {
00769 addTri( vfront, ifront, front[0], front[2], front[3], frontEdges, splitFront, plane );
00770 }
00771
00772 if ( bcount == 4 )
00773 {
00774 addTri( vback, iback, back[0], back[2], back[3], backEdges, splitBack, plane );
00775 }
00776 #endif
00777 }
00778 break;
00779 }
00780 }
00781
00782
00783
00784
00785
00786
00787 if ( frontEdges.size() )
00788 {
00789 UintVector polygon;
00790
00791 bool ok = extractPolygon(frontEdges,polygon,splitFront);
00792
00793 while ( ok )
00794 {
00795
00796 const double *vertices = Vl_getVertices(splitFront);
00797 unsigned int pcount = polygon.size();
00798 unsigned int maxTri = pcount*3;
00799 double *tris = new double[maxTri*9];
00800
00801 unsigned int tcount = triangulate3d(pcount,(const unsigned int *) &polygon[0], vertices, tris, maxTri, plane );
00802
00803 if ( tcount )
00804 {
00805
00806 const double *source = tris;
00807 for (unsigned int i=0; i<tcount; i++)
00808 {
00809 unsigned int i1 = Vl_getIndex(vfront, &source[0] );
00810 unsigned int i2 = Vl_getIndex(vfront, &source[3] );
00811 unsigned int i3 = Vl_getIndex(vfront, &source[6] );
00812
00813 ifront.push_back(i1);
00814 ifront.push_back(i2);
00815 ifront.push_back(i3);
00816
00817 ifront.push_back(i3);
00818 ifront.push_back(i2);
00819 ifront.push_back(i1);
00820
00821
00822 source+=9;
00823 }
00824 }
00825 delete tris;
00826 ok = extractPolygon(frontEdges,polygon,splitFront);
00827 }
00828 }
00829
00830
00831 if ( backEdges.size() )
00832 {
00833 UintVector polygon;
00834
00835 bool ok = extractPolygon(backEdges,polygon,splitBack);
00836
00837 while ( ok )
00838 {
00839
00840 const double *vertices = Vl_getVertices(splitBack);
00841 unsigned int pcount = polygon.size();
00842 unsigned int maxTri = pcount*3;
00843 double *tris = new double[maxTri*9];
00844
00845 unsigned int tcount = triangulate3d(pcount,(const unsigned int *) &polygon[0], vertices, tris, maxTri, plane );
00846
00847 if ( tcount )
00848 {
00849
00850 const double *source = tris;
00851 for (unsigned int i=0; i<tcount; i++)
00852 {
00853 unsigned int i1 = Vl_getIndex(vback, &source[0] );
00854 unsigned int i2 = Vl_getIndex(vback, &source[3] );
00855 unsigned int i3 = Vl_getIndex(vback, &source[6] );
00856
00857 iback.push_back(i1);
00858 iback.push_back(i2);
00859 iback.push_back(i3);
00860
00861 iback.push_back(i3);
00862 iback.push_back(i2);
00863 iback.push_back(i1);
00864
00865
00866 source+=9;
00867 }
00868 }
00869 delete tris;
00870 ok = extractPolygon(backEdges,polygon,splitBack);
00871 }
00872 }
00873
00874 #if CLOSE_FACE
00875 saveObj(vfront,ifront,true);
00876 saveObj(vback,iback,false);
00877 #endif
00878
00879 Vl_releaseVertexLookup(splitFront);
00880 Vl_releaseVertexLookup(splitBack);
00881
00882 unsigned int fsize = ifront.size()/3;
00883 unsigned int bsize = iback.size()/3;
00884
00885
00886 if ( ifront.size() )
00887 {
00888 unsigned int vcount = Vl_getVcount(vfront);
00889 const double *vertices = Vl_getVertices(vfront);
00890 unsigned int tcount = ifront.size()/3;
00891
00892 doConvexDecomposition(vcount, vertices, tcount, &ifront[0], callback, masterVolume, depth+1);
00893
00894 }
00895
00896 ifront.clear();
00897
00898 Vl_releaseVertexLookup(vfront);
00899
00900 if ( iback.size() )
00901 {
00902 unsigned int vcount = Vl_getVcount(vback);
00903 const double *vertices = Vl_getVertices(vback);
00904 unsigned int tcount = iback.size()/3;
00905
00906 doConvexDecomposition(vcount, vertices, tcount, &iback[0], callback, masterVolume, depth+1);
00907
00908 }
00909
00910 iback.clear();
00911 Vl_releaseVertexLookup(vback);
00912
00913 }
00914 }
00915
00916 int findFirstUnused(EdgeVector &edges) const
00917 {
00918 int ret = -1;
00919
00920 for (int i=0; i<(int)edges.size(); i++)
00921 {
00922 if ( !edges[i].mUsed )
00923 {
00924 edges[i].mUsed = true;
00925 ret = i;
00926 printf("%d edges, found root at %d\r\n", (int)edges.size(), ret );
00927 break;
00928 }
00929 }
00930
00931 for (int i=0; i<(int)edges.size(); i++)
00932 {
00933 const char *used = "false";
00934 if ( edges[i].mUsed ) used = "true";
00935 printf("Edge%d : %d to %d used: %s\r\n", i, edges[i].mE1, edges[i].mE2, used );
00936 }
00937
00938
00939 return ret;
00940 }
00941
00942 int findEdge(EdgeVector &edges,unsigned int index) const
00943 {
00944 int ret = -1;
00945
00946 for (int i=0; i<(int)edges.size(); i++)
00947 {
00948 if ( !edges[i].mUsed && edges[i].mE1 == index )
00949 {
00950 edges[i].mUsed = true;
00951 printf("Found matching unused edge %d matching (%d)\r\n", i, index );
00952 ret = i;
00953 break;
00954 }
00955 }
00956
00957 if ( ret == -1 )
00958 {
00959 printf("Failed to find a match for edge '%d'\r\n", index );
00960 }
00961
00962 return ret;
00963 }
00964
00965 int findNearestEdge(EdgeVector &edges,unsigned int index,VertexLookup verts) const
00966 {
00967 int ret = -1;
00968
00969
00970 const double *vertices = Vl_getVertices(verts);
00971 const double *pos = &vertices[index*3];
00972 double closest = 0.2f*0.2f;
00973
00974 for (int i=0; i<(int)edges.size(); i++)
00975 {
00976 Edge &e = edges[i];
00977
00978 if ( !e.mUsed )
00979 {
00980 const double *dpos = &vertices[ e.mE1*3 ];
00981 double dx = pos[0] - dpos[0];
00982 double dy = pos[1] - dpos[1];
00983 double dz = pos[2] - dpos[2];
00984 double dist = dx*dx+dy*dy+dz*dz;
00985 if ( dist < closest )
00986 {
00987 closest = dist;
00988 ret = i;
00989 }
00990 }
00991 }
00992
00993 if ( ret == -1 )
00994 {
00995 printf("Failed to find a match for edge '%d'\r\n", index );
00996 }
00997 else
00998 {
00999 edges[ret].mUsed = true;
01000 }
01001
01002 return ret;
01003 }
01004
01005 bool extractPolygon(EdgeVector &edges,UintVector &polygon,VertexLookup split)
01006 {
01007 bool ret = false;
01008
01009
01010 polygon.clear();
01011
01012 int root = findFirstUnused(edges);
01013
01014 if ( root >= 0 )
01015 {
01016 Edge &e = edges[root];
01017 polygon.push_back(e.mE1);
01018 int link;
01019
01020 do
01021 {
01022 link = findEdge(edges,e.mE2);
01023 if ( link < 0 )
01024 link = findNearestEdge(edges,e.mE2,split);
01025
01026 if ( link >= 0 )
01027 {
01028 e = edges[link];
01029 polygon.push_back(e.mE1 );
01030 }
01031 } while ( link >= 0 );
01032
01033
01034 if ( polygon.size() >= 3 )
01035 {
01036 ret = true;
01037 }
01038
01039 }
01040
01041 return ret;
01042 }
01043
01044 CHullVector mChulls;
01045 ConvexDecompInterface *mCallback;
01046
01047 };
01048
01049 unsigned int performConvexDecomposition(const DecompDesc &desc)
01050 {
01051 unsigned int ret = 0;
01052
01053 if ( desc.mCallback )
01054 {
01055 ConvexBuilder cb(desc.mCallback);
01056
01057 ret = cb.process(desc);
01058 }
01059
01060 return ret;
01061 }
01062
01063
01064
01065 };