btMultiBodyWorldImporter.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523
  1. #include "btMultiBodyWorldImporter.h"
  2. #include "LinearMath/btSerializer.h"
  3. #include "../BulletFileLoader/btBulletFile.h"
  4. #include "btBulletWorldImporter.h"
  5. #include "btBulletDynamicsCommon.h"
  6. #include "BulletDynamics/Featherstone/btMultiBody.h"
  7. #include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
  8. #include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
  9. struct btMultiBodyWorldImporterInternalData
  10. {
  11. btMultiBodyDynamicsWorld* m_mbDynamicsWorld;
  12. btHashMap<btHashPtr, btMultiBody*> m_mbMap;
  13. };
  14. btMultiBodyWorldImporter::btMultiBodyWorldImporter(btMultiBodyDynamicsWorld* world)
  15. :btBulletWorldImporter(world)
  16. {
  17. m_data = new btMultiBodyWorldImporterInternalData;
  18. m_data->m_mbDynamicsWorld = world;
  19. }
  20. btMultiBodyWorldImporter::~btMultiBodyWorldImporter()
  21. {
  22. delete m_data;
  23. }
  24. void btMultiBodyWorldImporter::deleteAllData()
  25. {
  26. btBulletWorldImporter::deleteAllData();
  27. }
  28. static btCollisionObjectDoubleData* getBody0FromContactManifold(btPersistentManifoldDoubleData* manifold)
  29. {
  30. return (btCollisionObjectDoubleData*)manifold->m_body0;
  31. }
  32. static btCollisionObjectDoubleData* getBody1FromContactManifold(btPersistentManifoldDoubleData* manifold)
  33. {
  34. return (btCollisionObjectDoubleData*)manifold->m_body1;
  35. }
  36. static btCollisionObjectFloatData* getBody0FromContactManifold(btPersistentManifoldFloatData* manifold)
  37. {
  38. return (btCollisionObjectFloatData*)manifold->m_body0;
  39. }
  40. static btCollisionObjectFloatData* getBody1FromContactManifold(btPersistentManifoldFloatData* manifold)
  41. {
  42. return (btCollisionObjectFloatData*)manifold->m_body1;
  43. }
  44. template<class T> void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMultiBodyWorldImporterInternalData* m_data)
  45. {
  46. m_data->m_mbDynamicsWorld->updateAabbs();
  47. m_data->m_mbDynamicsWorld->computeOverlappingPairs();
  48. btDispatcher* dispatcher = m_data->m_mbDynamicsWorld->getDispatcher();
  49. btDispatcherInfo& dispatchInfo = m_data->m_mbDynamicsWorld->getDispatchInfo();
  50. if (dispatcher)
  51. {
  52. btOverlappingPairCache* pairCache = m_data->m_mbDynamicsWorld->getBroadphase()->getOverlappingPairCache();
  53. if (dispatcher)
  54. {
  55. dispatcher->dispatchAllCollisionPairs(pairCache, dispatchInfo, dispatcher);
  56. }
  57. int numExistingManifolds = m_data->m_mbDynamicsWorld->getDispatcher()->getNumManifolds();
  58. btManifoldArray manifoldArray;
  59. for (int i = 0; i < pairCache->getNumOverlappingPairs(); i++)
  60. {
  61. btBroadphasePair& pair = pairCache->getOverlappingPairArray()[i];
  62. if (pair.m_algorithm)
  63. {
  64. pair.m_algorithm->getAllContactManifolds(manifoldArray);
  65. //for each existing manifold, search a matching manifoldData and reconstruct
  66. for (int m = 0; m < manifoldArray.size(); m++)
  67. {
  68. btPersistentManifold* existingManifold = manifoldArray[m];
  69. int uid0 = existingManifold->getBody0()->getBroadphaseHandle()->m_uniqueId;
  70. int uid1 = existingManifold->getBody1()->getBroadphaseHandle()->m_uniqueId;
  71. int matchingManifoldIndex = -1;
  72. for (int q = 0; q < numContactManifolds; q++)
  73. {
  74. if (uid0 == getBody0FromContactManifold(contactManifolds[q])->m_uniqueId && uid1 == getBody1FromContactManifold(contactManifolds[q])->m_uniqueId)
  75. {
  76. matchingManifoldIndex = q;
  77. }
  78. }
  79. if (matchingManifoldIndex >= 0)
  80. {
  81. existingManifold->deSerialize(contactManifolds[matchingManifoldIndex]);
  82. }
  83. else
  84. {
  85. existingManifold->setNumContacts(0);
  86. //printf("Issue: cannot find maching contact manifold (%d, %d), may cause issues in determinism.\n", uid0, uid1);
  87. }
  88. manifoldArray.clear();
  89. }
  90. }
  91. }
  92. }
  93. }
  94. template<class T> void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldImporterInternalData* m_data, btAlignedObjectArray<btQuaternion>& scratchQ, btAlignedObjectArray<btVector3>& scratchM)
  95. {
  96. bool isFixedBase = mbd->m_baseMass == 0;
  97. bool canSleep = false;
  98. btVector3 baseInertia;
  99. baseInertia.deSerialize(mbd->m_baseInertia);
  100. btVector3 baseWorldPos;
  101. baseWorldPos.deSerialize(mbd->m_baseWorldPosition);
  102. mb->setBasePos(baseWorldPos);
  103. btQuaternion baseWorldRot;
  104. baseWorldRot.deSerialize(mbd->m_baseWorldOrientation);
  105. mb->setWorldToBaseRot(baseWorldRot.inverse());
  106. btVector3 baseLinVal;
  107. baseLinVal.deSerialize(mbd->m_baseLinearVelocity);
  108. btVector3 baseAngVel;
  109. baseAngVel.deSerialize(mbd->m_baseAngularVelocity);
  110. mb->setBaseVel(baseLinVal);
  111. mb->setBaseOmega(baseAngVel);
  112. for (int i = 0; i < mbd->m_numLinks; i++)
  113. {
  114. mb->getLink(i).m_absFrameTotVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityTop);
  115. mb->getLink(i).m_absFrameTotVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityBottom);
  116. mb->getLink(i).m_absFrameLocVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityTop);
  117. mb->getLink(i).m_absFrameLocVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityBottom);
  118. switch (mbd->m_links[i].m_jointType)
  119. {
  120. case btMultibodyLink::eFixed:
  121. {
  122. break;
  123. }
  124. case btMultibodyLink::ePrismatic:
  125. {
  126. mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
  127. mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
  128. break;
  129. }
  130. case btMultibodyLink::eRevolute:
  131. {
  132. mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
  133. mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
  134. break;
  135. }
  136. case btMultibodyLink::eSpherical:
  137. {
  138. btScalar jointPos[4] = { (btScalar)mbd->m_links[i].m_jointPos[0], (btScalar)mbd->m_links[i].m_jointPos[1], (btScalar)mbd->m_links[i].m_jointPos[2], (btScalar)mbd->m_links[i].m_jointPos[3] };
  139. btScalar jointVel[3] = { (btScalar)mbd->m_links[i].m_jointVel[0], (btScalar)mbd->m_links[i].m_jointVel[1], (btScalar)mbd->m_links[i].m_jointVel[2] };
  140. mb->setJointPosMultiDof(i, jointPos);
  141. mb->setJointVelMultiDof(i, jointVel);
  142. break;
  143. }
  144. case btMultibodyLink::ePlanar:
  145. {
  146. break;
  147. }
  148. default:
  149. {
  150. }
  151. }
  152. }
  153. mb->forwardKinematics(scratchQ, scratchM);
  154. mb->updateCollisionObjectWorldTransforms(scratchQ, scratchM);
  155. }
  156. template<class T> void convertMultiBody(T* mbd, btMultiBodyWorldImporterInternalData* m_data)
  157. {
  158. bool isFixedBase = mbd->m_baseMass == 0;
  159. bool canSleep = false;
  160. btVector3 baseInertia;
  161. baseInertia.deSerialize(mbd->m_baseInertia);
  162. btMultiBody* mb = new btMultiBody(mbd->m_numLinks, mbd->m_baseMass, baseInertia, isFixedBase, canSleep);
  163. mb->setHasSelfCollision(false);
  164. btVector3 baseWorldPos;
  165. baseWorldPos.deSerialize(mbd->m_baseWorldPosition);
  166. btQuaternion baseWorldOrn;
  167. baseWorldOrn.deSerialize(mbd->m_baseWorldOrientation);
  168. mb->setBasePos(baseWorldPos);
  169. mb->setWorldToBaseRot(baseWorldOrn.inverse());
  170. m_data->m_mbMap.insert(mbd, mb);
  171. for (int i = 0; i < mbd->m_numLinks; i++)
  172. {
  173. btVector3 localInertiaDiagonal;
  174. localInertiaDiagonal.deSerialize(mbd->m_links[i].m_linkInertia);
  175. btQuaternion parentRotToThis;
  176. parentRotToThis.deSerialize(mbd->m_links[i].m_zeroRotParentToThis);
  177. btVector3 parentComToThisPivotOffset;
  178. parentComToThisPivotOffset.deSerialize(mbd->m_links[i].m_parentComToThisPivotOffset);
  179. btVector3 thisPivotToThisComOffset;
  180. thisPivotToThisComOffset.deSerialize(mbd->m_links[i].m_thisPivotToThisComOffset);
  181. switch (mbd->m_links[i].m_jointType)
  182. {
  183. case btMultibodyLink::eFixed:
  184. {
  185. mb->setupFixed(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
  186. parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset);
  187. //search for the collider
  188. //mbd->m_links[i].m_linkCollider
  189. break;
  190. }
  191. case btMultibodyLink::ePrismatic:
  192. {
  193. btVector3 jointAxis;
  194. jointAxis.deSerialize(mbd->m_links[i].m_jointAxisBottom[0]);
  195. bool disableParentCollision = true;//todo
  196. mb->setupPrismatic(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
  197. parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
  198. mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
  199. mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
  200. break;
  201. }
  202. case btMultibodyLink::eRevolute:
  203. {
  204. btVector3 jointAxis;
  205. jointAxis.deSerialize(mbd->m_links[i].m_jointAxisTop[0]);
  206. bool disableParentCollision = true;//todo
  207. mb->setupRevolute(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
  208. parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
  209. mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
  210. mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
  211. break;
  212. }
  213. case btMultibodyLink::eSpherical:
  214. {
  215. btAssert(0);
  216. bool disableParentCollision = true;//todo
  217. mb->setupSpherical(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
  218. parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
  219. btScalar jointPos[4] = { (btScalar)mbd->m_links[i].m_jointPos[0], (btScalar)mbd->m_links[i].m_jointPos[1], (btScalar)mbd->m_links[i].m_jointPos[2], (btScalar)mbd->m_links[i].m_jointPos[3] };
  220. btScalar jointVel[3] = { (btScalar)mbd->m_links[i].m_jointVel[0], (btScalar)mbd->m_links[i].m_jointVel[1], (btScalar)mbd->m_links[i].m_jointVel[2] };
  221. mb->setJointPosMultiDof(i, jointPos);
  222. mb->setJointVelMultiDof(i, jointVel);
  223. break;
  224. }
  225. case btMultibodyLink::ePlanar:
  226. {
  227. btAssert(0);
  228. break;
  229. }
  230. default:
  231. {
  232. btAssert(0);
  233. }
  234. }
  235. }
  236. }
  237. bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile2)
  238. {
  239. bool result = false;
  240. btAlignedObjectArray<btQuaternion> scratchQ;
  241. btAlignedObjectArray<btVector3> scratchM;
  242. if (m_importerFlags&eRESTORE_EXISTING_OBJECTS)
  243. {
  244. //check if the snapshot is valid for the existing world
  245. //equal number of objects, # links etc
  246. if ((bulletFile2->m_multiBodies.size() != m_data->m_mbDynamicsWorld->getNumMultibodies()))
  247. {
  248. result = false;
  249. return result;
  250. }
  251. result = true;
  252. //convert all multibodies
  253. if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
  254. {
  255. //for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
  256. for (int i = bulletFile2->m_multiBodies.size() - 1; i >= 0; i--)
  257. {
  258. btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*)bulletFile2->m_multiBodies[i];
  259. btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i);
  260. syncMultiBody(mbd, mb, m_data, scratchQ, scratchM);
  261. }
  262. for (int i = bulletFile2->m_rigidBodies.size() - 1; i >= 0; i--)
  263. {
  264. btRigidBodyDoubleData* rbd = (btRigidBodyDoubleData*)bulletFile2->m_rigidBodies[i];
  265. int foundRb = -1;
  266. int uid = rbd->m_collisionObjectData.m_uniqueId;
  267. for (int i = 0; i < m_data->m_mbDynamicsWorld->getNumCollisionObjects(); i++)
  268. {
  269. if (uid == m_data->m_mbDynamicsWorld->getCollisionObjectArray()[i]->getBroadphaseHandle()->m_uniqueId)
  270. {
  271. foundRb = i;
  272. break;
  273. }
  274. }
  275. if (foundRb >= 0)
  276. {
  277. btRigidBody* rb = btRigidBody::upcast(m_data->m_mbDynamicsWorld->getCollisionObjectArray()[foundRb]);
  278. if (rb)
  279. {
  280. btTransform tr;
  281. tr.deSerializeDouble(rbd->m_collisionObjectData.m_worldTransform);
  282. rb->setWorldTransform(tr);
  283. btVector3 linVel, angVel;
  284. linVel.deSerializeDouble(rbd->m_linearVelocity);
  285. angVel.deSerializeDouble(rbd->m_angularVelocity);
  286. rb->setLinearVelocity(linVel);
  287. rb->setAngularVelocity(angVel);
  288. }
  289. else
  290. {
  291. result = false;
  292. }
  293. }
  294. else
  295. {
  296. result = false;
  297. }
  298. }
  299. //todo: check why body1 pointer is not properly deserialized
  300. for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++)
  301. {
  302. btPersistentManifoldDoubleData* manifoldData = (btPersistentManifoldDoubleData*)bulletFile2->m_contactManifolds[i];
  303. {
  304. void* ptr = bulletFile2->findLibPointer(manifoldData->m_body0);
  305. if (ptr)
  306. {
  307. manifoldData->m_body0 = (btCollisionObjectDoubleData*)ptr;
  308. }
  309. }
  310. {
  311. void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1);
  312. if (ptr)
  313. {
  314. manifoldData->m_body1 = (btCollisionObjectDoubleData*)ptr;
  315. }
  316. }
  317. }
  318. if (bulletFile2->m_contactManifolds.size())
  319. {
  320. syncContactManifolds((btPersistentManifoldDoubleData**)&bulletFile2->m_contactManifolds[0], bulletFile2->m_contactManifolds.size(), m_data);
  321. }
  322. }
  323. else
  324. {
  325. //single precision version
  326. //for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
  327. for (int i = bulletFile2->m_multiBodies.size() - 1; i >= 0; i--)
  328. {
  329. btMultiBodyFloatData* mbd = (btMultiBodyFloatData*)bulletFile2->m_multiBodies[i];
  330. btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i);
  331. syncMultiBody(mbd, mb, m_data, scratchQ, scratchM);
  332. }
  333. //todo: check why body1 pointer is not properly deserialized
  334. for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++)
  335. {
  336. btPersistentManifoldFloatData* manifoldData = (btPersistentManifoldFloatData*)bulletFile2->m_contactManifolds[i];
  337. {
  338. void* ptr = bulletFile2->findLibPointer(manifoldData->m_body0);
  339. if (ptr)
  340. {
  341. manifoldData->m_body0 = (btCollisionObjectFloatData*)ptr;
  342. }
  343. }
  344. {
  345. void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1);
  346. if (ptr)
  347. {
  348. manifoldData->m_body1 = (btCollisionObjectFloatData*)ptr;
  349. }
  350. }
  351. }
  352. if (bulletFile2->m_contactManifolds.size())
  353. {
  354. syncContactManifolds((btPersistentManifoldFloatData**)&bulletFile2->m_contactManifolds[0], bulletFile2->m_contactManifolds.size(), m_data);
  355. }
  356. }
  357. }
  358. else
  359. {
  360. result = btBulletWorldImporter::convertAllObjects(bulletFile2);
  361. //convert all multibodies
  362. for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
  363. {
  364. if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
  365. {
  366. btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*)bulletFile2->m_multiBodies[i];
  367. convertMultiBody(mbd, m_data);
  368. }
  369. else
  370. {
  371. btMultiBodyFloatData* mbd = (btMultiBodyFloatData*)bulletFile2->m_multiBodies[i];
  372. convertMultiBody(mbd, m_data);
  373. }
  374. }
  375. //forward kinematics, so that the link world transforms are valid, for collision detection
  376. for (int i = 0; i < m_data->m_mbMap.size(); i++)
  377. {
  378. btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i);
  379. if (ptr)
  380. {
  381. btMultiBody* mb = *ptr;
  382. mb->finalizeMultiDof();
  383. btVector3 linvel = mb->getBaseVel();
  384. btVector3 angvel = mb->getBaseOmega();
  385. mb->forwardKinematics(scratchQ, scratchM);
  386. }
  387. }
  388. //convert all multibody link colliders
  389. for (int i = 0; i < bulletFile2->m_multiBodyLinkColliders.size(); i++)
  390. {
  391. if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
  392. {
  393. btMultiBodyLinkColliderDoubleData* mblcd = (btMultiBodyLinkColliderDoubleData*)bulletFile2->m_multiBodyLinkColliders[i];
  394. btMultiBody** ptr = m_data->m_mbMap[mblcd->m_multiBody];
  395. if (ptr)
  396. {
  397. btMultiBody* multiBody = *ptr;
  398. btCollisionShape** shapePtr = m_shapeMap.find(mblcd->m_colObjData.m_collisionShape);
  399. if (shapePtr && *shapePtr)
  400. {
  401. btTransform startTransform;
  402. mblcd->m_colObjData.m_worldTransform.m_origin.m_floats[3] = 0.f;
  403. startTransform.deSerializeDouble(mblcd->m_colObjData.m_worldTransform);
  404. btCollisionShape* shape = (btCollisionShape*)*shapePtr;
  405. if (shape)
  406. {
  407. btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(multiBody, mblcd->m_link);
  408. col->setCollisionShape(shape);
  409. //btCollisionObject* body = createCollisionObject(startTransform,shape,mblcd->m_colObjData.m_name);
  410. col->setFriction(btScalar(mblcd->m_colObjData.m_friction));
  411. col->setRestitution(btScalar(mblcd->m_colObjData.m_restitution));
  412. //m_bodyMap.insert(colObjData,body);
  413. if (mblcd->m_link == -1)
  414. {
  415. col->setWorldTransform(multiBody->getBaseWorldTransform());
  416. multiBody->setBaseCollider(col);
  417. }
  418. else
  419. {
  420. col->setWorldTransform(multiBody->getLink(mblcd->m_link).m_cachedWorldTransform);
  421. multiBody->getLink(mblcd->m_link).m_collider = col;
  422. }
  423. int mbLinkIndex = mblcd->m_link;
  424. bool isDynamic = (mbLinkIndex < 0 && multiBody->hasFixedBase()) ? false : true;
  425. int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
  426. int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
  427. #if 0
  428. int colGroup = 0, colMask = 0;
  429. int collisionFlags = mblcd->m_colObjData.m_collisionFlags;
  430. if (collisionFlags & URDF_HAS_COLLISION_GROUP)
  431. {
  432. collisionFilterGroup = colGroup;
  433. }
  434. if (collisionFlags & URDF_HAS_COLLISION_MASK)
  435. {
  436. collisionFilterMask = colMask;
  437. }
  438. #endif
  439. m_data->m_mbDynamicsWorld->addCollisionObject(col, collisionFilterGroup, collisionFilterMask);
  440. }
  441. }
  442. else
  443. {
  444. printf("error: no shape found\n");
  445. }
  446. #if 0
  447. //base and fixed? -> static, otherwise flag as dynamic
  448. world1->addCollisionObject(col, collisionFilterGroup, collisionFilterMask);
  449. #endif
  450. }
  451. }
  452. }
  453. for (int i = 0; i < m_data->m_mbMap.size(); i++)
  454. {
  455. btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i);
  456. if (ptr)
  457. {
  458. btMultiBody* mb = *ptr;
  459. mb->finalizeMultiDof();
  460. m_data->m_mbDynamicsWorld->addMultiBody(mb);
  461. }
  462. }
  463. }
  464. return result;
  465. }