obj2sdf.cpp 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216
  1. /// obj2sdf will load a Wavefront .obj file that may contain many parts/materials
  2. /// it will split into separate obj files for each part/material and
  3. /// create an sdf file with visuals/collisions pointing to the new obj files
  4. /// this will make it easier to load complex obj files into pybullet
  5. /// see for example export in data/kitchens/fathirmutfak.sdf
  6. #include <string.h>
  7. #include <stdio.h>
  8. #include <assert.h>
  9. #define ASSERT_EQ(a,b) assert((a)==(b));
  10. #include"Wavefront/tiny_obj_loader.h"
  11. #include <vector>
  12. #include "Bullet3Common/b3FileUtils.h"
  13. #include "../Utils/b3ResourcePath.h"
  14. #include "Bullet3Common/b3CommandLineArgs.h"
  15. #define MAX_PATH_LEN 1024
  16. std::string StripExtension( const std::string & sPath )
  17. {
  18. for( std::string::const_reverse_iterator i = sPath.rbegin(); i != sPath.rend(); i++ )
  19. {
  20. if( *i == '.' )
  21. {
  22. return std::string( sPath.begin(), i.base() - 1 );
  23. }
  24. // if we find a slash there is no extension
  25. if( *i == '\\' || *i == '/' )
  26. break;
  27. }
  28. // we didn't find an extension
  29. return sPath;
  30. }
  31. int main(int argc, char* argv[])
  32. {
  33. b3CommandLineArgs args(argc,argv);
  34. char* fileName;
  35. args.GetCmdLineArgument("fileName",fileName);
  36. if (fileName==0)
  37. {
  38. printf("required --fileName=\"name\"");
  39. exit(0);
  40. }
  41. std::string matLibName = StripExtension(fileName);
  42. printf("fileName = %s\n", fileName);
  43. if (fileName==0)
  44. {
  45. printf("Please use --fileName=\"pathToObj\".");
  46. exit(0);
  47. }
  48. char fileNameWithPath[MAX_PATH_LEN];
  49. bool fileFound = (b3ResourcePath::findResourcePath(fileName,fileNameWithPath,MAX_PATH_LEN))>0;
  50. char materialPrefixPath[MAX_PATH_LEN];
  51. b3FileUtils::extractPath(fileNameWithPath,materialPrefixPath,MAX_PATH_LEN);
  52. std::vector<tinyobj::shape_t> shapes;
  53. std::string err = tinyobj::LoadObj(shapes, fileNameWithPath, materialPrefixPath);
  54. char sdfFileName[MAX_PATH_LEN];
  55. sprintf(sdfFileName,"%s%s.sdf",materialPrefixPath,"newsdf");
  56. FILE* sdfFile = fopen(sdfFileName,"w");
  57. if (sdfFile==0)
  58. {
  59. printf("Fatal error: cannot create sdf file %s\n",sdfFileName);
  60. exit(0);
  61. }
  62. fprintf(sdfFile, "<sdf version='1.6'>\n\t<world name='default'>\n\t<gravity>0 0 -9.8</gravity>\n");
  63. for (int s=0;s<(int)shapes.size();s++)
  64. {
  65. tinyobj::shape_t& shape = shapes[s];
  66. if (shape.name.length())
  67. {
  68. printf("object name = %s\n", shape.name.c_str());
  69. }
  70. char objFileName[MAX_PATH_LEN];
  71. if (strlen(materialPrefixPath)>0)
  72. {
  73. sprintf(objFileName,"%s/part%d.obj",materialPrefixPath,s);
  74. } else
  75. {
  76. sprintf(objFileName,"part%d.obj",s);
  77. }
  78. FILE* f = fopen(objFileName,"w");
  79. if (f==0)
  80. {
  81. printf("Fatal error: cannot create part obj file %s\n",objFileName);
  82. exit(0);
  83. }
  84. fprintf(f,"# Exported using automatic converter by Erwin Coumans\n");
  85. if (matLibName.length())
  86. {
  87. fprintf(f,"mtllib %s.mtl\n", matLibName.c_str());
  88. } else
  89. {
  90. fprintf(f,"mtllib bedroom.mtl\n");
  91. }
  92. int faceCount = shape.mesh.indices.size();
  93. int vertexCount = shape.mesh.positions.size();
  94. tinyobj::material_t mat = shape.material;
  95. if (shape.name.length())
  96. {
  97. const char* objName = shape.name.c_str();
  98. printf("mat.name = %s\n", objName);
  99. fprintf(f,"#object %s\n\n",objName);
  100. }
  101. for (int v=0;v<vertexCount/3;v++)
  102. {
  103. fprintf(f,"v %f %f %f\n",shape.mesh.positions[v*3+0],shape.mesh.positions[v*3+1],shape.mesh.positions[v*3+2]);
  104. }
  105. if (mat.name.length())
  106. {
  107. fprintf(f,"usemtl %s\n",mat.name.c_str());
  108. } else
  109. {
  110. fprintf(f,"usemtl wire_028089177\n");
  111. }
  112. fprintf(f,"\n");
  113. int numNormals = int(shape.mesh.normals.size());
  114. for (int vn = 0;vn<numNormals/3;vn++)
  115. {
  116. fprintf(f,"vn %f %f %f\n",shape.mesh.normals[vn*3+0],shape.mesh.normals[vn*3+1],shape.mesh.normals[vn*3+2]);
  117. }
  118. fprintf(f,"\n");
  119. int numTexCoords = int(shape.mesh.texcoords.size());
  120. for (int vt = 0;vt<numTexCoords/2;vt++)
  121. {
  122. fprintf(f,"vt %f %f\n",shape.mesh.texcoords[vt*2+0],shape.mesh.texcoords[vt*2+1]);
  123. }
  124. fprintf(f,"s off\n");
  125. for (int face=0;face<faceCount;face+=3)
  126. {
  127. if (face<0 && face>=int(shape.mesh.indices.size()))
  128. {
  129. continue;
  130. }
  131. fprintf(f,"f %d/%d/%d %d/%d/%d %d/%d/%d\n",
  132. shape.mesh.indices[face]+1,shape.mesh.indices[face]+1,shape.mesh.indices[face]+1,
  133. shape.mesh.indices[face+1]+1,shape.mesh.indices[face+1]+1,shape.mesh.indices[face+1]+1,
  134. shape.mesh.indices[face+2]+1,shape.mesh.indices[face+2]+1,shape.mesh.indices[face+2]+1);
  135. }
  136. fclose(f);
  137. float kdRed=mat.diffuse[0];
  138. float kdGreen=mat.diffuse[1];
  139. float kdBlue=mat.diffuse[2];
  140. char objSdfPartFileName[MAX_PATH_LEN];
  141. sprintf(objSdfPartFileName,"part%d.obj",s);
  142. fprintf(sdfFile,"\t\t<model name='%s'>\n"
  143. "\t\t\t<static>1</static>\n"
  144. "\t\t\t<pose frame=''>0 0 0 0 0 0</pose>\n"
  145. "\t\t\t<link name='link_d%d'>\n"
  146. "\t\t\t<inertial>\n"
  147. "\t\t\t<mass>0</mass>\n"
  148. "\t\t\t<inertia>\n"
  149. "\t\t\t<ixx>0.166667</ixx>\n"
  150. "\t\t\t<ixy>0</ixy>\n"
  151. "\t\t\t<ixz>0</ixz>\n"
  152. "\t\t\t<iyy>0.166667</iyy>\n"
  153. "\t\t\t<iyz>0</iyz>\n"
  154. "\t\t\t<izz>0.166667</izz>\n"
  155. "\t\t\t</inertia>\n"
  156. "\t\t\t</inertial>\n"
  157. "\t\t\t<collision name='collision_%d'>\n"
  158. "\t\t\t<geometry>\n"
  159. "\t\t\t<mesh>\n"
  160. "\t\t\t<scale>1 1 1</scale>\n"
  161. "\t\t\t\t<uri>%s</uri>\n"
  162. "\t\t\t</mesh>\n"
  163. "\t\t\t</geometry>\n"
  164. "\t\t\t </collision>\n"
  165. "\t\t\t<visual name='visual'>\n"
  166. "\t\t\t\t<geometry>\n"
  167. "\t\t\t\t<mesh>\n"
  168. "\t\t\t\t\t<scale>1 1 1</scale>\n"
  169. "\t\t\t\t\t<uri>%s</uri>\n"
  170. "\t\t\t\t</mesh>\n"
  171. "\t\t\t\t</geometry>\n"
  172. "\t\t\t<material>\n"
  173. "\t\t\t\t<ambient>1 0 0 1</ambient>\n"
  174. "\t\t\t\t<diffuse>%f %f %f 1</diffuse>\n"
  175. "\t\t\t\t<specular>0.1 0.1 0.1 1</specular>\n"
  176. "\t\t\t\t<emissive>0 0 0 0</emissive>\n"
  177. "\t\t\t </material>\n"
  178. "\t\t\t </visual>\n"
  179. "\t\t\t </link>\n"
  180. "\t\t\t</model>\n",objSdfPartFileName,s,s,
  181. objSdfPartFileName,objSdfPartFileName,
  182. kdRed, kdGreen, kdBlue);
  183. }
  184. fprintf(sdfFile,"\t</world>\n</sdf>\n");
  185. fclose(sdfFile);
  186. return 0;
  187. }