obj2sdf.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452
  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. #include "Bullet3Common/b3HashMap.h"
  16. struct ShapeContainer
  17. {
  18. std::string m_matName;
  19. std::string m_shapeName;
  20. tinyobj::material_t material;
  21. std::vector<float> positions;
  22. std::vector<float> normals;
  23. std::vector<float> texcoords;
  24. std::vector<unsigned int> indices;
  25. b3AlignedObjectArray<int> m_shapeIndices;
  26. };
  27. b3HashMap<b3HashString, ShapeContainer> gMaterialNames;
  28. #define MAX_PATH_LEN 1024
  29. std::string StripExtension( const std::string & sPath )
  30. {
  31. for( std::string::const_reverse_iterator i = sPath.rbegin(); i != sPath.rend(); i++ )
  32. {
  33. if( *i == '.' )
  34. {
  35. return std::string( sPath.begin(), i.base() - 1 );
  36. }
  37. // if we find a slash there is no extension
  38. if( *i == '\\' || *i == '/' )
  39. break;
  40. }
  41. // we didn't find an extension
  42. return sPath;
  43. }
  44. int main(int argc, char* argv[])
  45. {
  46. b3CommandLineArgs args(argc,argv);
  47. char* fileName;
  48. args.GetCmdLineArgument("fileName",fileName);
  49. if (fileName==0)
  50. {
  51. printf("required --fileName=\"name\"");
  52. exit(0);
  53. }
  54. std::string matLibName = StripExtension(fileName);
  55. printf("fileName = %s\n", fileName);
  56. if (fileName==0)
  57. {
  58. printf("Please use --fileName=\"pathToObj\".");
  59. exit(0);
  60. }
  61. bool mergeMaterials = args.CheckCmdLineFlag("mergeMaterials");
  62. char fileNameWithPath[MAX_PATH_LEN];
  63. bool fileFound = (b3ResourcePath::findResourcePath(fileName,fileNameWithPath,MAX_PATH_LEN))>0;
  64. char materialPrefixPath[MAX_PATH_LEN];
  65. b3FileUtils::extractPath(fileNameWithPath,materialPrefixPath,MAX_PATH_LEN);
  66. std::vector<tinyobj::shape_t> shapes;
  67. std::string err = tinyobj::LoadObj(shapes, fileNameWithPath, materialPrefixPath);
  68. char sdfFileName[MAX_PATH_LEN];
  69. sprintf(sdfFileName,"%s%s.sdf",materialPrefixPath,"newsdf");
  70. FILE* sdfFile = fopen(sdfFileName,"w");
  71. if (sdfFile==0)
  72. {
  73. printf("Fatal error: cannot create sdf file %s\n",sdfFileName);
  74. exit(0);
  75. }
  76. fprintf(sdfFile, "<sdf version='1.6'>\n\t<world name='default'>\n\t<gravity>0 0 -9.8</gravity>\n");
  77. for (int s = 0; s < (int)shapes.size(); s++)
  78. {
  79. tinyobj::shape_t& shape = shapes[s];
  80. tinyobj::material_t mat = shape.material;
  81. b3HashString key = mat.name.length() ? mat.name.c_str() : "";
  82. if (!gMaterialNames.find(key))
  83. {
  84. ShapeContainer container;
  85. container.m_matName = mat.name;
  86. container.m_shapeName = shape.name;
  87. container.material = mat;
  88. gMaterialNames.insert(key, container);
  89. }
  90. ShapeContainer* shapeC = gMaterialNames.find(key);
  91. if (shapeC)
  92. {
  93. shapeC->m_shapeIndices.push_back(s);
  94. int curPositions = shapeC->positions.size()/3;
  95. int curNormals = shapeC->normals.size()/3;
  96. int curTexcoords = shapeC->texcoords.size()/2;
  97. int faceCount = shape.mesh.indices.size();
  98. int vertexCount = shape.mesh.positions.size();
  99. for (int v = 0; v < vertexCount; v++)
  100. {
  101. shapeC->positions.push_back(shape.mesh.positions[v]);
  102. }
  103. int numNormals = int(shape.mesh.normals.size());
  104. for (int vn = 0; vn < numNormals; vn++)
  105. {
  106. shapeC->normals.push_back(shape.mesh.normals[vn]);
  107. }
  108. int numTexCoords = int(shape.mesh.texcoords.size());
  109. for (int vt = 0; vt < numTexCoords; vt++)
  110. {
  111. shapeC->texcoords.push_back(shape.mesh.texcoords[vt]);
  112. }
  113. for (int face = 0; face < faceCount; face += 3)
  114. {
  115. if (face < 0 && face >= int(shape.mesh.indices.size()))
  116. {
  117. continue;
  118. }
  119. shapeC->indices.push_back(shape.mesh.indices[face] + curPositions);
  120. shapeC->indices.push_back(shape.mesh.indices[face+1] + curPositions);
  121. shapeC->indices.push_back(shape.mesh.indices[face + 2] + curPositions);
  122. }
  123. }
  124. }
  125. printf("unique materials=%d\n", gMaterialNames.size());
  126. if (mergeMaterials)
  127. {
  128. for (int m = 0; m < gMaterialNames.size();m++)
  129. {
  130. if (gMaterialNames.getAtIndex(m)->m_shapeIndices.size() == 0)
  131. continue;
  132. ShapeContainer* shapeCon =gMaterialNames.getAtIndex(m);
  133. printf("object name = %s\n", shapeCon->m_shapeName.c_str());
  134. char objSdfPartFileName[MAX_PATH_LEN];
  135. sprintf(objSdfPartFileName, "part%d.obj", m);
  136. char objFileName[MAX_PATH_LEN];
  137. if (strlen(materialPrefixPath) > 0)
  138. {
  139. sprintf(objFileName, "%s/part%d.obj", materialPrefixPath, m);
  140. }
  141. else
  142. {
  143. sprintf(objFileName, "part%d.obj", m);
  144. }
  145. FILE* f = fopen(objFileName, "w");
  146. if (f == 0)
  147. {
  148. printf("Fatal error: cannot create part obj file %s\n", objFileName);
  149. exit(0);
  150. }
  151. fprintf(f, "# Exported using automatic converter by Erwin Coumans\n");
  152. if (matLibName.length())
  153. {
  154. fprintf(f, "mtllib %s.mtl\n", matLibName.c_str());
  155. }
  156. else
  157. {
  158. fprintf(f, "mtllib bedroom.mtl\n");
  159. }
  160. int faceCount = shapeCon->indices.size();
  161. int vertexCount = shapeCon->positions.size();
  162. tinyobj::material_t mat = shapeCon->material;
  163. if (shapeCon->m_matName.length())
  164. {
  165. const char* objName = shapeCon->m_matName.c_str();
  166. printf("mat.name = %s\n", objName);
  167. fprintf(f, "#object %s\n\n", objName);
  168. }
  169. for (int v = 0; v < vertexCount / 3; v++)
  170. {
  171. fprintf(f, "v %f %f %f\n", shapeCon->positions[v * 3 + 0], shapeCon->positions[v * 3 + 1], shapeCon->positions[v * 3 + 2]);
  172. }
  173. if (mat.name.length())
  174. {
  175. fprintf(f, "usemtl %s\n", mat.name.c_str());
  176. }
  177. else
  178. {
  179. fprintf(f, "usemtl wire_028089177\n");
  180. }
  181. fprintf(f, "\n");
  182. int numNormals = int(shapeCon->normals.size());
  183. for (int vn = 0; vn < numNormals / 3; vn++)
  184. {
  185. fprintf(f, "vn %f %f %f\n", shapeCon->normals[vn * 3 + 0], shapeCon->normals[vn * 3 + 1], shapeCon->normals[vn * 3 + 2]);
  186. }
  187. fprintf(f, "\n");
  188. int numTexCoords = int(shapeCon->texcoords.size());
  189. for (int vt = 0; vt < numTexCoords / 2; vt++)
  190. {
  191. fprintf(f, "vt %f %f\n", shapeCon->texcoords[vt * 2 + 0], shapeCon->texcoords[vt * 2 + 1]);
  192. }
  193. fprintf(f, "s off\n");
  194. for (int face = 0; face < faceCount; face += 3)
  195. {
  196. if (face < 0 && face >= int(shapeCon->indices.size()))
  197. {
  198. continue;
  199. }
  200. fprintf(f, "f %d/%d/%d %d/%d/%d %d/%d/%d\n",
  201. shapeCon->indices[face] + 1, shapeCon->indices[face] + 1, shapeCon->indices[face] + 1,
  202. shapeCon->indices[face + 1] + 1, shapeCon->indices[face + 1] + 1, shapeCon->indices[face + 1] + 1,
  203. shapeCon->indices[face + 2] + 1, shapeCon->indices[face + 2] + 1, shapeCon->indices[face + 2] + 1);
  204. }
  205. fclose(f);
  206. float kdRed = mat.diffuse[0];
  207. float kdGreen = mat.diffuse[1];
  208. float kdBlue = mat.diffuse[2];
  209. float transparency = mat.transparency;
  210. fprintf(sdfFile, "\t\t<model name='%s'>\n"
  211. "\t\t\t<static>1</static>\n"
  212. "\t\t\t<pose frame=''>0 0 0 0 0 0</pose>\n"
  213. "\t\t\t<link name='link_d%d'>\n"
  214. "\t\t\t<inertial>\n"
  215. "\t\t\t<mass>0</mass>\n"
  216. "\t\t\t<inertia>\n"
  217. "\t\t\t<ixx>0.166667</ixx>\n"
  218. "\t\t\t<ixy>0</ixy>\n"
  219. "\t\t\t<ixz>0</ixz>\n"
  220. "\t\t\t<iyy>0.166667</iyy>\n"
  221. "\t\t\t<iyz>0</iyz>\n"
  222. "\t\t\t<izz>0.166667</izz>\n"
  223. "\t\t\t</inertia>\n"
  224. "\t\t\t</inertial>\n"
  225. "\t\t\t<collision concave='yes' name='collision_%d'>\n"
  226. "\t\t\t<geometry>\n"
  227. "\t\t\t<mesh>\n"
  228. "\t\t\t<scale>1 1 1</scale>\n"
  229. "\t\t\t\t<uri>%s</uri>\n"
  230. "\t\t\t</mesh>\n"
  231. "\t\t\t</geometry>\n"
  232. "\t\t\t </collision>\n"
  233. "\t\t\t<visual name='visual'>\n"
  234. "\t\t\t\t<geometry>\n"
  235. "\t\t\t\t<mesh>\n"
  236. "\t\t\t\t\t<scale>1 1 1</scale>\n"
  237. "\t\t\t\t\t<uri>%s</uri>\n"
  238. "\t\t\t\t</mesh>\n"
  239. "\t\t\t\t</geometry>\n"
  240. "\t\t\t<material>\n"
  241. "\t\t\t\t<ambient>1 0 0 1</ambient>\n"
  242. "\t\t\t\t<diffuse>%f %f %f %f</diffuse>\n"
  243. "\t\t\t\t<specular>0.1 0.1 0.1 1</specular>\n"
  244. "\t\t\t\t<emissive>0 0 0 0</emissive>\n"
  245. "\t\t\t </material>\n"
  246. "\t\t\t </visual>\n"
  247. "\t\t\t </link>\n"
  248. "\t\t\t</model>\n", objSdfPartFileName, m, m,
  249. objSdfPartFileName, objSdfPartFileName,
  250. kdRed, kdGreen, kdBlue, transparency);
  251. }
  252. }
  253. else
  254. {
  255. for (int s = 0; s < (int)shapes.size(); s++)
  256. {
  257. tinyobj::shape_t& shape = shapes[s];
  258. if (shape.name.length())
  259. {
  260. printf("object name = %s\n", shape.name.c_str());
  261. }
  262. char objFileName[MAX_PATH_LEN];
  263. if (strlen(materialPrefixPath) > 0)
  264. {
  265. sprintf(objFileName, "%s/part%d.obj", materialPrefixPath, s);
  266. }
  267. else
  268. {
  269. sprintf(objFileName, "part%d.obj", s);
  270. }
  271. FILE* f = fopen(objFileName, "w");
  272. if (f == 0)
  273. {
  274. printf("Fatal error: cannot create part obj file %s\n", objFileName);
  275. exit(0);
  276. }
  277. fprintf(f, "# Exported using automatic converter by Erwin Coumans\n");
  278. if (matLibName.length())
  279. {
  280. fprintf(f, "mtllib %s.mtl\n", matLibName.c_str());
  281. }
  282. else
  283. {
  284. fprintf(f, "mtllib bedroom.mtl\n");
  285. }
  286. int faceCount = shape.mesh.indices.size();
  287. int vertexCount = shape.mesh.positions.size();
  288. tinyobj::material_t mat = shape.material;
  289. if (shape.name.length())
  290. {
  291. const char* objName = shape.name.c_str();
  292. printf("mat.name = %s\n", objName);
  293. fprintf(f, "#object %s\n\n", objName);
  294. }
  295. for (int v = 0; v < vertexCount / 3; v++)
  296. {
  297. 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]);
  298. }
  299. if (mat.name.length())
  300. {
  301. fprintf(f, "usemtl %s\n", mat.name.c_str());
  302. }
  303. else
  304. {
  305. fprintf(f, "usemtl wire_028089177\n");
  306. }
  307. fprintf(f, "\n");
  308. int numNormals = int(shape.mesh.normals.size());
  309. for (int vn = 0; vn < numNormals / 3; vn++)
  310. {
  311. 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]);
  312. }
  313. fprintf(f, "\n");
  314. int numTexCoords = int(shape.mesh.texcoords.size());
  315. for (int vt = 0; vt < numTexCoords / 2; vt++)
  316. {
  317. fprintf(f, "vt %f %f\n", shape.mesh.texcoords[vt * 2 + 0], shape.mesh.texcoords[vt * 2 + 1]);
  318. }
  319. fprintf(f, "s off\n");
  320. for (int face = 0; face < faceCount; face += 3)
  321. {
  322. if (face < 0 && face >= int(shape.mesh.indices.size()))
  323. {
  324. continue;
  325. }
  326. fprintf(f, "f %d/%d/%d %d/%d/%d %d/%d/%d\n",
  327. shape.mesh.indices[face] + 1, shape.mesh.indices[face] + 1, shape.mesh.indices[face] + 1,
  328. shape.mesh.indices[face + 1] + 1, shape.mesh.indices[face + 1] + 1, shape.mesh.indices[face + 1] + 1,
  329. shape.mesh.indices[face + 2] + 1, shape.mesh.indices[face + 2] + 1, shape.mesh.indices[face + 2] + 1);
  330. }
  331. fclose(f);
  332. float kdRed = mat.diffuse[0];
  333. float kdGreen = mat.diffuse[1];
  334. float kdBlue = mat.diffuse[2];
  335. float transparency = mat.transparency;
  336. char objSdfPartFileName[MAX_PATH_LEN];
  337. sprintf(objSdfPartFileName, "part%d.obj", s);
  338. fprintf(sdfFile, "\t\t<model name='%s'>\n"
  339. "\t\t\t<static>1</static>\n"
  340. "\t\t\t<pose frame=''>0 0 0 0 0 0</pose>\n"
  341. "\t\t\t<link name='link_d%d'>\n"
  342. "\t\t\t<inertial>\n"
  343. "\t\t\t<mass>0</mass>\n"
  344. "\t\t\t<inertia>\n"
  345. "\t\t\t<ixx>0.166667</ixx>\n"
  346. "\t\t\t<ixy>0</ixy>\n"
  347. "\t\t\t<ixz>0</ixz>\n"
  348. "\t\t\t<iyy>0.166667</iyy>\n"
  349. "\t\t\t<iyz>0</iyz>\n"
  350. "\t\t\t<izz>0.166667</izz>\n"
  351. "\t\t\t</inertia>\n"
  352. "\t\t\t</inertial>\n"
  353. "\t\t\t<collision name='collision_%d'>\n"
  354. "\t\t\t<geometry>\n"
  355. "\t\t\t<mesh>\n"
  356. "\t\t\t<scale>1 1 1</scale>\n"
  357. "\t\t\t\t<uri>%s</uri>\n"
  358. "\t\t\t</mesh>\n"
  359. "\t\t\t</geometry>\n"
  360. "\t\t\t </collision>\n"
  361. "\t\t\t<visual name='visual'>\n"
  362. "\t\t\t\t<geometry>\n"
  363. "\t\t\t\t<mesh>\n"
  364. "\t\t\t\t\t<scale>1 1 1</scale>\n"
  365. "\t\t\t\t\t<uri>%s</uri>\n"
  366. "\t\t\t\t</mesh>\n"
  367. "\t\t\t\t</geometry>\n"
  368. "\t\t\t<material>\n"
  369. "\t\t\t\t<ambient>1 0 0 1</ambient>\n"
  370. "\t\t\t\t<diffuse>%f %f %f %f</diffuse>\n"
  371. "\t\t\t\t<specular>0.1 0.1 0.1 1</specular>\n"
  372. "\t\t\t\t<emissive>0 0 0 0</emissive>\n"
  373. "\t\t\t </material>\n"
  374. "\t\t\t </visual>\n"
  375. "\t\t\t </link>\n"
  376. "\t\t\t</model>\n", objSdfPartFileName, s, s,
  377. objSdfPartFileName, objSdfPartFileName,
  378. kdRed, kdGreen, kdBlue, transparency);
  379. }
  380. }
  381. fprintf(sdfFile,"\t</world>\n</sdf>\n");
  382. fclose(sdfFile);
  383. return 0;
  384. }