DecomposeSample.cpp
Go to the documentation of this file.
00001 #include <stdio.h>
00002 #include <stdlib.h>
00003 #include <string.h>
00004 #include <assert.h>
00005 #include <float.h>
00006 
00007 #include <vector>
00008 
00009 #include "./ConvexDecomposition/ConvexDecomposition.h"
00010 #include "./ConvexDecomposition/cd_wavefront.h"
00011 
00012 using namespace ConvexDecomposition;
00013 
00014 // Test application to demonstrate how to use the ConvexDecomposition system.
00015 
00016 typedef std::vector< ConvexResult * > ConvexResultVector;
00017 
00018 static const char * fstring(float v)
00019 {
00020         static char data[64*16];
00021         static int  index=0;
00022 
00023         char *ret = &data[index*64];
00024         index++;
00025         if (index == 16 ) index = 0;
00026 
00027         if ( v == FLT_MIN ) return "-INF";  // collada notation for FLT_MIN and FLT_MAX
00028         if ( v == FLT_MAX ) return "INF";
00029 
00030         if ( v == 1 )
00031         {
00032                 strcpy(ret,"1");
00033         }
00034         else if ( v == 0 )
00035         {
00036                 strcpy(ret,"0");
00037         }
00038         else if ( v == - 1 )
00039         {
00040                 strcpy(ret,"-1");
00041         }
00042         else
00043         {
00044                 sprintf(ret,"%.9f", v );
00045                 const char *dot = strstr(ret,".");
00046                 if ( dot )
00047                 {
00048                         int len = (int)strlen(ret);
00049                   char *foo = &ret[len-1];
00050                         while ( *foo == '0' ) foo--;
00051                         if ( *foo == '.' )
00052                                 *foo = 0;
00053                         else
00054                                 foo[1] = 0;
00055                 }
00056         }
00057 
00058         return ret;
00059 }
00060 
00061 class CBuilder : public ConvexDecompInterface
00062 {
00063 public:
00064 
00065   CBuilder(const char *fname,const DecompDesc &d)
00066   {
00067 
00068         strcpy(mBaseName,fname);
00069         char *dot = strstr(mBaseName,".obj");
00070         if ( dot ) *dot = 0;
00071 
00072                 sprintf(mObjName,"%s_convex.obj", mBaseName );
00073 
00074         mBaseCount = 0;
00075         mHullCount = 0;
00076         mSkinWidth = (float)d.mSkinWidth;
00077 
00078         mFph = fopen(mObjName,"wb");
00079 
00080 
00081                 printf("########################################################################\r\n");
00082         printf("# Perfomring approximate convex decomposition for triangle mesh %s\r\n", fname );
00083         printf("# Input Mesh has %d vertices and %d triangles.\r\n", d.mVcount, d.mTcount );
00084         printf("# Recursion depth: %d\r\n", d.mDepth );
00085         printf("# Concavity Threshold Percentage: %0.2f\r\n", d.mCpercent );
00086         printf("# Hull Merge Volume Percentage: %0.2f\r\n", d.mPpercent );
00087         printf("# Maximum output vertices per hull: %d\r\n", d.mMaxVertices );
00088         printf("# Hull Skin Width: %0.2f\r\n", d.mSkinWidth );
00089                 printf("########################################################################\r\n");
00090 
00091 
00092         if ( mFph )
00093         {
00094                         fprintf(mFph,"########################################################################\r\n");
00095                 fprintf(mFph,"# Approximate convex decomposition for triangle mesh %s\r\n", fname );
00096                 fprintf(mFph,"# Input Mesh has %d vertices and %d triangles.\r\n", d.mVcount, d.mTcount );
00097                 fprintf(mFph,"# Recursion depth: %d\r\n", d.mDepth );
00098                 fprintf(mFph,"# Concavity Threshold Percentage: %0.2f\r\n", d.mCpercent );
00099                 fprintf(mFph,"# Hull Merge Volume Percentage: %0.2f\r\n", d.mPpercent );
00100                 fprintf(mFph,"# Maximum output vertices per hull: %d\r\n", d.mMaxVertices );
00101                 fprintf(mFph,"# Hull Skin Width: %0.2f\r\n", d.mSkinWidth );
00102                         fprintf(mFph,"########################################################################\r\n");
00103 
00104                   printf("Opened Wavefront file %s for output.\r\n", mObjName );
00105         }
00106         else
00107         {
00108                 printf("Failed to open output file %s\r\n", mObjName );
00109         }
00110   }
00111 
00112         ~CBuilder(void)
00113         {
00114                 if ( mFph )
00115                 {
00116                         fclose(mFph);
00117                 }
00118     for (unsigned int i=0; i<mHulls.size(); i++)
00119     {
00120         ConvexResult *cr = mHulls[i];
00121         delete cr;
00122     }
00123         }
00124 
00125   virtual void ConvexDecompResult(ConvexResult &result)
00126   {
00127         // we have a hull...
00128         mHullCount++;
00129 
00130         printf("Received hull %d  HullVolume(%0.3f)\r\n", mHullCount, result.mHullVolume );
00131 
00132                 if ( mFph )
00133                 {
00134 
00135                         ConvexResult *cr = new ConvexResult(result);
00136                         mHulls.push_back(cr);
00137 
00138                         fprintf(mFph,"########################################################################\r\n");
00139                         fprintf(mFph,"## Hull Piece %d with %d vertices and %d triangles.\r\n", mHullCount, result.mHullVcount, result.mHullTcount );
00140                         fprintf(mFph,"########################################################################\r\n");
00141 
00142                         for (unsigned int i=0; i<result.mHullVcount; i++)
00143                         {
00144                                 const double *p = &result.mHullVertices[i*3];
00145                                 fprintf(mFph,"v %0.9f %0.9f %0.9f\r\n", (float)p[0], (float)p[1], (float)p[2] );
00146                         }
00147 
00148                         if ( 1 )
00149                         {
00150                                 const unsigned int *src = result.mHullIndices;
00151                                 for (unsigned int i=0; i<result.mHullTcount; i++)
00152                                 {
00153                                         unsigned int i1 = *src++;
00154                                         unsigned int i2 = *src++;
00155                                         unsigned int i3 = *src++;
00156 
00157           i1+=mBaseCount;
00158           i2+=mBaseCount;
00159           i3+=mBaseCount;
00160 
00161                                  fprintf(mFph,"f %d %d %d\r\n", i1+1, i2+1, i3+1 );
00162                                 }
00163                         }
00164                         mBaseCount+=result.mHullVcount; // advance the 'base index' counter.
00165                 }
00166 
00167   }
00168 
00169   void saveCOLLADA(FILE *fph,unsigned int index,ConvexResult *cr)
00170   {
00171 
00172     fprintf(fph,"    <geometry id=\"%s_%d-Mesh\" name=\"%s_%d-Mesh\">\r\n", mBaseName, index, mBaseName, index);
00173     fprintf(fph,"      <convex_mesh>\r\n");
00174     fprintf(fph,"        <source id=\"%s_%d-Position\">\r\n", mBaseName, index);
00175     fprintf(fph,"          <float_array count=\"%d\" id=\"%s_%d-Position-array\">\r\n", cr->mHullVcount*3, mBaseName, index);
00176     fprintf(fph,"            ");
00177     for (unsigned int i=0; i<cr->mHullVcount; i++)
00178     {
00179         const double *p = &cr->mHullVertices[i*3];
00180         fprintf(fph,"%s %s %s  ", fstring((float)p[0]), fstring((float)p[1]), fstring((float)p[2]) );
00181                         if ( ((i+1)&3) == 0 && (i+1) < cr->mHullVcount )
00182         {
00183                 fprintf(fph,"\r\n");
00184                 fprintf(fph,"            ");
00185         }
00186     }
00187     fprintf(fph,"\r\n");
00188     fprintf(fph,"          </float_array>\r\n");
00189     fprintf(fph,"          <technique_common>\r\n");
00190     fprintf(fph,"            <accessor count=\"%d\" source=\"#%s_%d-Position-array\" stride=\"3\">\r\n", cr->mHullVcount, mBaseName, index );
00191     fprintf(fph,"              <param name=\"X\" type=\"float\"/>\r\n");
00192     fprintf(fph,"              <param name=\"Y\" type=\"float\"/>\r\n");
00193     fprintf(fph,"              <param name=\"Z\" type=\"float\"/>\r\n");
00194     fprintf(fph,"            </accessor>\r\n");
00195     fprintf(fph,"                  </technique_common>\r\n");
00196     fprintf(fph,"                                </source>\r\n");
00197     fprintf(fph,"                <vertices id=\"%s_%d-Vertex\">\r\n", mBaseName, index);
00198     fprintf(fph,"                                       <input semantic=\"POSITION\" source=\"#%s_%d-Position\"/>\r\n", mBaseName, index);
00199     fprintf(fph,"                               </vertices>\r\n");
00200     fprintf(fph,"                               <triangles material=\"Material\" count=\"%d\">\r\n", cr->mHullTcount );
00201     fprintf(fph,"                                       <input offset=\"0\" semantic=\"VERTEX\" source=\"#%s_%d-Vertex\"/>\r\n", mBaseName, index);
00202     fprintf(fph,"           <p>\r\n");
00203     fprintf(fph,"             ");
00204     for (unsigned int i=0; i<cr->mHullTcount; i++)
00205     {
00206         unsigned int *tri = &cr->mHullIndices[i*3];
00207         fprintf(fph,"%d %d %d  ", tri[0], tri[1], tri[2] );
00208                         if ( ((i+1)&3) == 0 && (i+1) < cr->mHullTcount )
00209         {
00210                 fprintf(fph,"\r\n");
00211                 fprintf(fph,"             ");
00212         }
00213     }
00214     fprintf(fph,"\r\n");
00215     fprintf(fph,"           </p>\r\n");
00216     fprintf(fph,"                               </triangles>\r\n");
00217     fprintf(fph,"      </convex_mesh>\r\n");
00218     fprintf(fph,"               </geometry>\r\n");
00219 
00220   }
00221 
00222         void saveCOLLADA(void)
00223         {
00224         char scratch[512];
00225                 sprintf(scratch,"%s.dae", mBaseName );
00226                 FILE *fph = fopen(scratch,"wb");
00227 
00228         if ( fph )
00229         {
00230                 printf("Saving convex decomposition of %d hulls to COLLADA file '%s'\r\n", (int)mHulls.size(), scratch );
00231 
00232       fprintf(fph,"<?xml version=\"1.0\" encoding=\"utf-8\"?>\r\n");
00233       fprintf(fph,"<COLLADA version=\"1.4.0\" xmlns=\"http://www.collada.org/2005/11/COLLADASchema\">\r\n");
00234       fprintf(fph,"     <asset>\r\n");
00235       fprintf(fph,"             <contributor>\r\n");
00236       fprintf(fph,"                     <author>NxuStream2 converter - http://www.ageia.com</author>\r\n");
00237       fprintf(fph,"                     <authoring_tool>PhysX Rocket, PhysX Viewer, or CreateDynamics</authoring_tool>\r\n");
00238       fprintf(fph,"                     <comments>questions to: jratcliff@ageia.com</comments>\r\n");
00239       fprintf(fph,"                     <copyright></copyright>\r\n");
00240       fprintf(fph,"                     <source_data>chair_gothic_tilted</source_data>\r\n");
00241       fprintf(fph,"             </contributor>\r\n");
00242       fprintf(fph,"             <unit meter=\"1\" name=\"meter\"/>\r\n");
00243       fprintf(fph,"             <up_axis>Y_UP</up_axis>\r\n");
00244       fprintf(fph,"     </asset>\r\n");
00245       fprintf(fph,"   <library_materials>\r\n");
00246       fprintf(fph,"      <material id=\"Material\" name=\"Material\">\r\n");
00247       fprintf(fph,"         <instance_effect url=\"#Material-fx\"></instance_effect>\r\n");
00248       fprintf(fph,"      </material>\r\n");
00249       fprintf(fph,"   </library_materials>\r\n");
00250       fprintf(fph,"   <library_effects>\r\n");
00251       fprintf(fph,"      <effect id=\"Material-fx\" name=\"Material\">\r\n");
00252       fprintf(fph,"         <profile_COMMON>\r\n");
00253       fprintf(fph,"            <technique id=\"Material-fx-COMMON\" sid=\"COMMON\">\r\n");
00254       fprintf(fph,"               <phong>\r\n");
00255       fprintf(fph,"                  <ambient>\r\n");
00256       fprintf(fph,"                     <color>0.803922 0.588235 0.92549 1</color>\r\n");
00257       fprintf(fph,"                  </ambient>\r\n");
00258       fprintf(fph,"                  <diffuse>\r\n");
00259       fprintf(fph,"                     <color>0.803922 0.588235 0.92549 1</color>\r\n");
00260       fprintf(fph,"                  </diffuse>\r\n");
00261       fprintf(fph,"                  <specular>\r\n");
00262       fprintf(fph,"                     <color>0.631373 0.631373 0.631373 1</color>\r\n");
00263       fprintf(fph,"                  </specular>\r\n");
00264       fprintf(fph,"                  <shininess>\r\n");
00265       fprintf(fph,"                     <float>1</float>\r\n");
00266       fprintf(fph,"                  </shininess>\r\n");
00267       fprintf(fph,"                  <reflective>\r\n");
00268       fprintf(fph,"                     <color>0 0 0 1</color>\r\n");
00269       fprintf(fph,"                  </reflective>\r\n");
00270       fprintf(fph,"                  <transparent>\r\n");
00271       fprintf(fph,"                     <color>1 1 1 1</color>\r\n");
00272       fprintf(fph,"                  </transparent>\r\n");
00273       fprintf(fph,"                  <transparency>\r\n");
00274       fprintf(fph,"                     <float>0</float>\r\n");
00275       fprintf(fph,"                  </transparency>\r\n");
00276       fprintf(fph,"               </phong>\r\n");
00277       fprintf(fph,"           </technique>\r\n");
00278       fprintf(fph,"         </profile_COMMON>\r\n");
00279       fprintf(fph,"      </effect>\r\n");
00280       fprintf(fph,"   </library_effects>\r\n");
00281       fprintf(fph,"  <library_geometries>\r\n");
00282 
00283       for (unsigned int i=0; i<mHulls.size(); i++)
00284       {
00285         ConvexResult *cr = mHulls[i];
00286         saveCOLLADA(fph,i,cr);
00287       }
00288 
00289 
00290       fprintf(fph,"  </library_geometries>\r\n");
00291       fprintf(fph,"  <library_visual_scenes>\r\n");
00292       fprintf(fph,"       <visual_scene id=\"Scene0-Visual\" name=\"Scene0-Visual\">\r\n");
00293       fprintf(fph,"      <node id=\"%s-Node\" name=\"%s\" type=\"NODE\">\r\n", mBaseName, mBaseName );
00294       fprintf(fph,"        <translate>0 0 0</translate>\r\n");
00295       fprintf(fph,"        <rotate>1 0 0  0</rotate>\r\n");
00296       fprintf(fph,"      </node>\r\n");
00297       fprintf(fph,"       </visual_scene>\r\n");
00298       fprintf(fph,"  </library_visual_scenes>\r\n");
00299       fprintf(fph,"  <library_physics_materials>\r\n");
00300       fprintf(fph,"    <physics_material id=\"pmat0_0-PhysicsMaterial\" name=\"pmat0_0-PhysicsMaterial\">\r\n");
00301       fprintf(fph,"      <technique_common>\r\n");
00302       fprintf(fph,"        <dynamic_friction>0.5</dynamic_friction>\r\n");
00303       fprintf(fph,"        <restitution>0</restitution>\r\n");
00304       fprintf(fph,"        <static_friction>0.5</static_friction>\r\n");
00305       fprintf(fph,"      </technique_common>\r\n");
00306       fprintf(fph,"    </physics_material>\r\n");
00307       fprintf(fph,"  </library_physics_materials>\r\n");
00308       fprintf(fph,"  <library_physics_models>\r\n");
00309       fprintf(fph,"    <physics_model id=\"Scene0-PhysicsModel\">\r\n");
00310       fprintf(fph,"      <rigid_body sid=\"%s-RigidBody\" name=\"%s\">\r\n", mBaseName, mBaseName);
00311       fprintf(fph,"        <technique_common>\r\n");
00312       fprintf(fph,"          <instance_physics_material url=\"#pmat0_0-PhysicsMaterial\"/>\r\n");
00313 
00314       for (unsigned int i=0; i<mHulls.size(); i++)
00315       {
00316         ConvexResult *ch = mHulls[i];
00317         fprintf(fph,"         <shape>\r\n");
00318         fprintf(fph,"            <translate>0 0 0</translate>\r\n");
00319         fprintf(fph,"            <rotate>1 0 0  0</rotate>\r\n");
00320         fprintf(fph,"            <instance_physics_material url=\"#pmat0_0-PhysicsMaterial\"/>\r\n");
00321         fprintf(fph,"            <density>1</density>\r\n");
00322         fprintf(fph,"            <extra>\r\n");
00323         fprintf(fph,"              <technique profile=\"PhysX\">\r\n");
00324         fprintf(fph,"               <skinWidth>%s</skinWidth>\r\n", fstring( mSkinWidth ) );
00325         fprintf(fph,"              </technique>\r\n");
00326         fprintf(fph,"            </extra>\r\n");
00327         fprintf(fph,"            <instance_geometry url=\"%s_%d-Mesh\"/>\r\n", mBaseName, i);
00328         fprintf(fph,"         </shape>\r\n");
00329       }
00330 
00331       fprintf(fph,"        <dynamic>true</dynamic>\r\n");
00332       fprintf(fph,"        <mass>1</mass>\r\n");
00333       fprintf(fph,"                     </technique_common>\r\n");
00334       fprintf(fph,"        <extra>\r\n");
00335       fprintf(fph,"          <technique profile=\"PhysX\">\r\n");
00336       fprintf(fph,"            <extra>\r\n");
00337       fprintf(fph,"              <technique profile=\"PhysX\">\r\n");
00338       fprintf(fph,"                <linearDamping>0</linearDamping>\r\n");
00339       fprintf(fph,"                <angularDamping>0</angularDamping>\r\n");
00340       fprintf(fph,"                <solverIterationCount>32</solverIterationCount>\r\n");
00341       fprintf(fph,"              </technique>\r\n");
00342       fprintf(fph,"            </extra>\r\n");
00343       fprintf(fph,"            <disable_collision>false</disable_collision>\r\n");
00344       fprintf(fph,"          </technique>\r\n");
00345       fprintf(fph,"        </extra>\r\n");
00346       fprintf(fph,"       </rigid_body>\r\n");
00347       fprintf(fph,"    </physics_model>\r\n");
00348       fprintf(fph,"  </library_physics_models>\r\n");
00349       fprintf(fph,"  <library_physics_scenes>\r\n");
00350       fprintf(fph,"    <physics_scene id=\"Scene0-Physics\">\r\n");
00351       fprintf(fph,"      <instance_physics_model url=\"#Scene0-PhysicsModel\">\r\n");
00352       fprintf(fph,"        <instance_rigid_body target=\"#%s-Node\" body=\"%s-RigidBody\"/>\r\n", mBaseName, mBaseName );
00353       fprintf(fph,"      <extra>\r\n");
00354       fprintf(fph,"        <technique profile=\"PhysX\">\r\n");
00355       fprintf(fph,"        </technique>\r\n");
00356       fprintf(fph,"      </extra>\r\n");
00357       fprintf(fph,"      </instance_physics_model>\r\n");
00358       fprintf(fph,"      <technique_common>\r\n");
00359       fprintf(fph,"        <gravity>0 -9.800000191 0</gravity>\r\n");
00360       fprintf(fph,"      </technique_common>\r\n");
00361       fprintf(fph,"    </physics_scene>\r\n");
00362       fprintf(fph,"  </library_physics_scenes>\r\n");
00363       fprintf(fph,"  <scene>\r\n");
00364       fprintf(fph,"    <instance_visual_scene url=\"#Scene0-Visual\"/>\r\n");
00365       fprintf(fph,"    <instance_physics_scene url=\"#Scene0-Physics\"/>\r\n");
00366       fprintf(fph,"  </scene>\r\n");
00367       fprintf(fph,"</COLLADA>\r\n");
00368 
00369 
00370       fclose(fph);
00371         }
00372         else
00373         {
00374                 printf("Failed to open file '%s' for write access.\r\n", scratch );
00375         }
00376         }
00377 
00378         void saveXML(FILE *fph,unsigned int index,ConvexResult *cr)
00379         {
00380 
00381     fprintf(fph,"  <NxConvexMeshDesc id=\"%s_%d\">\r\n", mBaseName, index);
00382     fprintf(fph,"    <points>\r\n");
00383                 fprintf(fph,"      ");
00384     for (unsigned int i=0; i<cr->mHullVcount; i++)
00385     {
00386         const double *p = &cr->mHullVertices[i*3];
00387         fprintf(fph,"%s %s %s  ", fstring((float)p[0]), fstring((float)p[1]), fstring((float)p[2]) );
00388                         if ( ((i+1)&3) == 0 && (i+1) < cr->mHullVcount )
00389         {
00390                 fprintf(fph,"\r\n");
00391                 fprintf(fph,"      ");
00392         }
00393     }
00394     fprintf(fph,"\r\n");
00395     fprintf(fph,"    </points>\r\n");
00396     fprintf(fph,"    <triangles>\r\n");
00397                 fprintf(fph,"      ");
00398     for (unsigned int i=0; i<cr->mHullTcount; i++)
00399     {
00400         unsigned int *tri = &cr->mHullIndices[i*3];
00401         fprintf(fph,"%d %d %d  ", tri[0], tri[1], tri[2] );
00402                         if ( ((i+1)&3) == 0 && (i+1) < cr->mHullTcount )
00403         {
00404                 fprintf(fph,"\r\n");
00405                 fprintf(fph,"      ");
00406         }
00407     }
00408     fprintf(fph,"\r\n");
00409     fprintf(fph,"    </triangles>\r\n");
00410     fprintf(fph,"  </NxConvexMeshDesc>\r\n");
00411 
00412         }
00413 
00414   void saveNxuStream(void)
00415   {
00416         char scratch[512];
00417                 sprintf(scratch,"%s.xml", mBaseName );
00418                 FILE *fph = fopen(scratch,"wb");
00419 
00420         if ( fph )
00421         {
00422           printf("Saving convex decomposition of %d hulls to NxuStream file '%s'\r\n", (int)mHulls.size(), scratch );
00423 
00424       fprintf(fph,"<?xml version=\"1.0\" encoding=\"utf-8\"?>\r\n");
00425       fprintf(fph,"  <NXUSTREAM2>\r\n");
00426       fprintf(fph,"    <NxuPhysicsCollection id=\"beshon\" sdkVersion=\"244\" nxuVersion=\"100\">\r\n");
00427       fprintf(fph,"      <NxPhysicsSDKDesc id=\"SDK\">\r\n");
00428       fprintf(fph,"        <hwPageSize>65536</hwPageSize>\r\n");
00429       fprintf(fph,"        <hwPageMax>256</hwPageMax>\r\n");
00430       fprintf(fph,"        <hwConvexMax>2048</hwConvexMax>\r\n");
00431       fprintf(fph,"      </NxPhysicsSDKDesc>\r\n");
00432 
00433                         for (unsigned int i=0; i<mHulls.size(); i++)
00434                         {
00435                                 saveXML(fph, i, mHulls[i] );
00436                         }
00437 
00438 
00439       fprintf(fph,"  <NxSceneDesc id=\"%s\">\r\n", mBaseName);
00440       fprintf(fph,"        <filterBool>false</filterBool>\r\n");
00441       fprintf(fph,"        <filterOp0>NX_FILTEROP_AND</filterOp0>\r\n");
00442       fprintf(fph,"        <filterOp1>NX_FILTEROP_AND</filterOp1>\r\n");
00443       fprintf(fph,"        <filterOp2>NX_FILTEROP_AND</filterOp2>\r\n");
00444       fprintf(fph,"        <NxGroupsMask id=\"groupMask0\" bits0=\"0\" bits1=\"0\" bits2=\"0\" bits3=\"0\"/>\r\n");
00445       fprintf(fph,"        <NxGroupsMask id=\"groupMask1\" bits0=\"0\" bits1=\"0\" bits2=\"0\" bits3=\"0\"/>\r\n");
00446       fprintf(fph,"        <gravity>0 -9.800000191 0</gravity>\r\n");
00447       fprintf(fph,"        <maxTimestep>0.016666668</maxTimestep>\r\n");
00448       fprintf(fph,"        <maxIter>8</maxIter>\r\n");
00449       fprintf(fph,"        <timeStepMethod>NX_TIMESTEP_FIXED</timeStepMethod>\r\n");
00450       fprintf(fph,"        <maxBounds>FLT_MIN FLT_MIN FLT_MIN  FLT_MAX FLT_MAX FLT_MAX</maxBounds>\r\n");
00451       fprintf(fph,"        <NxSceneLimits id=\"limits\">\r\n");
00452       fprintf(fph,"          <maxNbActors>0</maxNbActors>\r\n");
00453       fprintf(fph,"          <maxNbBodies>0</maxNbBodies>\r\n");
00454       fprintf(fph,"          <maxNbStaticShapes>0</maxNbStaticShapes>\r\n");
00455       fprintf(fph,"          <maxNbDynamicShapes>0</maxNbDynamicShapes>\r\n");
00456       fprintf(fph,"          <maxNbJoints>0</maxNbJoints>\r\n");
00457       fprintf(fph,"        </NxSceneLimits>\r\n");
00458       fprintf(fph,"        <simType>NX_SIMULATION_SW</simType>\r\n");
00459       fprintf(fph,"        <groundPlane>true</groundPlane>\r\n");
00460       fprintf(fph,"        <boundsPlanes>false</boundsPlanes>\r\n");
00461       fprintf(fph,"        <NxSceneFlags id=\"flags\">\r\n");
00462       fprintf(fph,"          <NX_SF_DISABLE_SSE>false</NX_SF_DISABLE_SSE>\r\n");
00463       fprintf(fph,"          <NX_SF_DISABLE_COLLISIONS>false</NX_SF_DISABLE_COLLISIONS>\r\n");
00464       fprintf(fph,"          <NX_SF_SIMULATE_SEPARATE_THREAD>true</NX_SF_SIMULATE_SEPARATE_THREAD>\r\n");
00465       fprintf(fph,"          <NX_SF_ENABLE_MULTITHREAD>false</NX_SF_ENABLE_MULTITHREAD>\r\n");
00466       fprintf(fph,"        </NxSceneFlags>\r\n");
00467       fprintf(fph,"        <internalThreadCount>0</internalThreadCount>\r\n");
00468       fprintf(fph,"        <backgroundThreadCount>0</backgroundThreadCount>\r\n");
00469       fprintf(fph,"        <threadMask>1431655764</threadMask>\r\n");
00470       fprintf(fph,"        <backgroundThreadMask>1431655764</backgroundThreadMask>\r\n");
00471       fprintf(fph,"        <NxMaterialDesc id=\"Material_0\" userProperties=\"\" hasSpring=\"false\" materialIndex=\"0\">\r\n");
00472       fprintf(fph,"          <dynamicFriction>0.5</dynamicFriction>\r\n");
00473       fprintf(fph,"          <staticFriction>0.5</staticFriction>\r\n");
00474       fprintf(fph,"          <restitution>0</restitution>\r\n");
00475       fprintf(fph,"          <dynamicFrictionV>0</dynamicFrictionV>\r\n");
00476       fprintf(fph,"          <staticFrictionV>0</staticFrictionV>\r\n");
00477       fprintf(fph,"          <frictionCombineMode>NX_CM_AVERAGE</frictionCombineMode>\r\n");
00478       fprintf(fph,"          <restitutionCombineMode>NX_CM_AVERAGE</restitutionCombineMode>\r\n");
00479       fprintf(fph,"          <dirOfAnisotropy>1 0 0</dirOfAnisotropy>\r\n");
00480       fprintf(fph,"          <NxMaterialFlag id=\"flags\">\r\n");
00481       fprintf(fph,"            <NX_MF_ANISOTROPIC>false</NX_MF_ANISOTROPIC>\r\n");
00482       fprintf(fph,"            <NX_MF_DISABLE_FRICTION>false</NX_MF_DISABLE_FRICTION>\r\n");
00483       fprintf(fph,"            <NX_MF_DISABLE_STRONG_FRICTION>false</NX_MF_DISABLE_STRONG_FRICTION>\r\n");
00484       fprintf(fph,"          </NxMaterialFlag>\r\n");
00485       fprintf(fph,"        </NxMaterialDesc>\r\n");
00486       fprintf(fph,"    <NxActorDesc id=\"%s\" userProperties=\"\" hasBody=\"true\" name=\"%s\">\r\n", mBaseName, mBaseName);
00487       fprintf(fph,"      <globalPose>1 0 0    0 1 0    0 0 1    0 0 0 </globalPose>\r\n");
00488       fprintf(fph,"                     <NxBodyDesc>\r\n");
00489       fprintf(fph,"        <mass>1</mass>\r\n");
00490       fprintf(fph,"        <linearDamping>0</linearDamping>\r\n");
00491       fprintf(fph,"        <angularDamping>0</angularDamping>\r\n");
00492       fprintf(fph,"        <solverIterationCount>32</solverIterationCount>\r\n");
00493       fprintf(fph,"        <NxBodyFlag id=\"flags\">\r\n");
00494       fprintf(fph,"          <NX_BF_POSE_SLEEP_TEST>true</NX_BF_POSE_SLEEP_TEST>\r\n");
00495       fprintf(fph,"          <NX_AF_DISABLE_COLLISION>false</NX_AF_DISABLE_COLLISION>\r\n");
00496       fprintf(fph,"        </NxBodyFlag>\r\n");
00497       fprintf(fph,"      </NxBodyDesc>\r\n");
00498       fprintf(fph,"      <name>Bip01 Pelvis</name>\r\n");
00499       for (unsigned int i=0; i<mHulls.size(); i++)
00500       {
00501         fprintf(fph,"      <NxConvexShapeDesc id=\"Shape_%d\" meshData=\"%s_%d\">\r\n", i, mBaseName, i);
00502         fprintf(fph,"      <NxShapeDesc>\r\n");
00503         fprintf(fph,"        <localPose>1 0 0    0 1 0    0 0 1    0 0 0 </localPose>\r\n");
00504         fprintf(fph,"        <skinWidth>0</skinWidth>\r\n");
00505         fprintf(fph,"      </NxShapeDesc>\r\n");
00506         fprintf(fph,"      </NxConvexShapeDesc>\r\n");
00507       }
00508       fprintf(fph,"    </NxActorDesc>\r\n");
00509 
00510       fprintf(fph,"  </NxSceneDesc>\r\n");
00511       fprintf(fph,"      <NxSceneInstance id=\"%s\">\r\n", mBaseName);
00512       fprintf(fph,"              <sceneName>beshon</sceneName>\r\n");
00513       fprintf(fph,"              <NxuUserProperties></NxuUserProperties>\r\n");
00514       fprintf(fph,"              <rootNode>1    0       0       0       1       0       0       0       1       0       0 0</rootNode>\r\n");
00515       fprintf(fph,"              <newScene>false</newScene>\r\n");
00516       fprintf(fph,"              <ignorePlane>true</ignorePlane>\r\n");
00517       fprintf(fph,"              <numSceneInstances>0</numSceneInstances>\r\n");
00518       fprintf(fph,"      </NxSceneInstance>\r\n");
00519       fprintf(fph,"  </NxuPhysicsCollection>\r\n");
00520       fprintf(fph,"</NXUSTREAM2>\r\n");
00521 
00522     }
00523     else
00524     {
00525         printf("Failed to open file '%s' for write access.\r\n", scratch );
00526     }
00527   }
00528 
00529   float             mSkinWidth;
00530         unsigned int      mHullCount;
00531   FILE              *mFph;
00532   unsigned int       mBaseCount;
00533   char               mObjName[512];
00534   char               mBaseName[512];
00535   ConvexResultVector mHulls;
00536 
00537 };
00538 
00539 
00540 int main(int argc,const char **argv)
00541 {
00542         if ( argc < 2 )
00543         {
00544                 printf("Usage: Test <meshanme.obj> (options)\r\n");
00545                 printf("\r\n");
00546                 printf("Options:\r\n");
00547                 printf("\r\n");
00548                 printf("            -d<depth>       : How deep to recursively split. Values of 3-7 are reasonable.\r\n");
00549                 printf("            -c<percent>     : Percentage of concavity to keep splitting. 0-20%% is reasonable.\r\n");
00550                 printf("            -p<percent>     : Percentage of volume delta to collapse hulls.  0-30%% is reasonable.\r\n");
00551                 printf("            -v<maxverts>    : Maximum number of vertices in the output hull.  Default is 32.\r\n");
00552                 printf("            -s<skinwidth>   : Skin Width inflation.  Default is 0.\r\n");
00553         }
00554         else
00555         {
00556                 unsigned int depth = 5;
00557                 float cpercent     = 5;
00558                 float ppercent     = 5;
00559                 unsigned int maxv  = 32;
00560                 float skinWidth    = 0;
00561 
00562                 // process command line switches.
00563                 for (int i=2; i<argc; i++)
00564                 {
00565                         const char *o = argv[i];
00566 
00567                         if ( strncmp(o,"-d",2) == 0 )
00568                         {
00569                                 depth = (unsigned int) atoi( &o[2] );
00570                                 if ( depth < 0 || depth > 10 )
00571                                 {
00572                                         depth = 5;
00573                                         printf("Invalid depth value in switch, defaulting to 5.\r\n");
00574                                 }
00575                         }
00576 
00577                         if ( strncmp(o,"-c",2) == 0 )
00578                         {
00579                                 cpercent = (float) atof( &o[2] );
00580                                 if ( cpercent < 0 || cpercent > 100 )
00581                                 {
00582                                         cpercent = 5;
00583                                         printf("Invalid concavity percentage in switch, defaulting to 5.\r\n");
00584                                 }
00585                         }
00586 
00587                         if ( strncmp(o,"-p",2) == 0 )
00588                         {
00589                                 ppercent = (float) atof( &o[2] );
00590                                 if ( ppercent < 0 || ppercent > 100 )
00591                                 {
00592                                         ppercent = 5;
00593                                         printf("Invalid hull merge percentage in switch, defaulting to 5.\r\n");
00594                                 }
00595                         }
00596 
00597                         if ( strncmp(o,"-v",2) == 0 )
00598                         {
00599                                 maxv = (unsigned int) atoi( &o[2] );
00600                                 if ( maxv < 8 || maxv > 256 )
00601                                 {
00602                                         maxv = 32;
00603                                         printf("Invalid max vertices in switch, defaulting to 32.\r\n");
00604                                 }
00605                         }
00606 
00607                         if ( strncmp(o,"-s",2) == 0 )
00608                         {
00609                                 skinWidth = (float) atof( &o[2] );
00610                                 if ( skinWidth < 0 || skinWidth > 0.1f )
00611                                 {
00612                                         skinWidth = 0;
00613                                         printf("Invalid skinWidth in switch, defaulting to 0.\r\n");
00614                                 }
00615                         }
00616 
00617                 }
00618 
00619                 WavefrontObj wo;
00620 
00621     unsigned int tcount = wo.loadObj(argv[1]);
00622 
00623     if ( tcount )
00624     {
00625 
00626 
00627         DecompDesc d;
00628 
00629       d.mVcount       = wo.mVertexCount;
00630       d.mVertices     = wo.mVertices;
00631       d.mTcount       = wo.mTriCount;
00632       d.mIndices      = (unsigned int *)wo.mIndices;
00633       d.mDepth        = depth;
00634       d.mCpercent     = cpercent;
00635       d.mPpercent     = ppercent;
00636       d.mMaxVertices  = maxv;
00637       d.mSkinWidth    = skinWidth;
00638 
00639 
00640         CBuilder   cb(argv[1],d); // receives the answers and writes out a wavefront OBJ file.
00641 
00642       d.mCallback     = &cb;
00643 
00644                         unsigned int count = performConvexDecomposition(d);
00645 
00646                         if ( count )
00647                         {
00648                                 printf("Input triangle mesh with %d triangles produced %d output hulls.\r\n", d.mTcount, count );
00649 
00650                           cb.saveNxuStream();  // save results in NxuStream format.
00651                           cb.saveCOLLADA();    // save results in COLLADA physics 1.4.1 format.
00652 
00653                         }
00654                         else
00655                         {
00656                                 printf("Failed to produce any convex hulls.\r\n");
00657                         }
00658 
00659     }
00660     else
00661     {
00662         // sorry..no
00663         printf("Sorry unable to load file '%s'\r\n", argv[1] );
00664     }
00665 
00666         }
00667 
00668 }


convex_decomposition
Author(s): John W. Ratcliff
autogenerated on Sat Jun 8 2019 20:01:17