Bullet Collision Detection & Physics Library
btMultiBodyWorldImporter.cpp
Go to the documentation of this file.
2
10
16
23
28
33
50
51template <class T>
52void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMultiBodyWorldImporterInternalData* m_data)
53{
56 btDispatcher* dispatcher = m_data->m_mbDynamicsWorld->getDispatcher();
57
58 btDispatcherInfo& dispatchInfo = m_data->m_mbDynamicsWorld->getDispatchInfo();
59
60 if (dispatcher)
61 {
63 if (dispatcher)
64 {
65 dispatcher->dispatchAllCollisionPairs(pairCache, dispatchInfo, dispatcher);
66 }
67 int numExistingManifolds = m_data->m_mbDynamicsWorld->getDispatcher()->getNumManifolds();
68 btManifoldArray manifoldArray;
69 for (int i = 0; i < pairCache->getNumOverlappingPairs(); i++)
70 {
71 btBroadphasePair& pair = pairCache->getOverlappingPairArray()[i];
72 if (pair.m_algorithm)
73 {
74 pair.m_algorithm->getAllContactManifolds(manifoldArray);
75 //for each existing manifold, search a matching manifoldData and reconstruct
76 for (int m = 0; m < manifoldArray.size(); m++)
77 {
78 btPersistentManifold* existingManifold = manifoldArray[m];
79 int uid0 = existingManifold->getBody0()->getBroadphaseHandle()->m_uniqueId;
80 int uid1 = existingManifold->getBody1()->getBroadphaseHandle()->m_uniqueId;
81 int matchingManifoldIndex = -1;
82 for (int q = 0; q < numContactManifolds; q++)
83 {
84 if (uid0 == getBody0FromContactManifold(contactManifolds[q])->m_uniqueId && uid1 == getBody1FromContactManifold(contactManifolds[q])->m_uniqueId)
85 {
86 matchingManifoldIndex = q;
87 }
88 }
89 if (matchingManifoldIndex >= 0)
90 {
91 existingManifold->deSerialize(contactManifolds[matchingManifoldIndex]);
92 }
93 else
94 {
95 existingManifold->setNumContacts(0);
96 //printf("Issue: cannot find maching contact manifold (%d, %d), may cause issues in determinism.\n", uid0, uid1);
97 }
98
99 manifoldArray.clear();
100 }
101 }
102 }
103 }
104}
105
106template <class T>
108{
109 bool isFixedBase = mbd->m_baseMass == 0;
110 bool canSleep = false;
111 btVector3 baseInertia;
112 baseInertia.deSerialize(mbd->m_baseInertia);
113
114 btVector3 baseWorldPos;
115 baseWorldPos.deSerialize(mbd->m_baseWorldPosition);
116 mb->setBasePos(baseWorldPos);
117 btQuaternion baseWorldRot;
118 baseWorldRot.deSerialize(mbd->m_baseWorldOrientation);
119 mb->setWorldToBaseRot(baseWorldRot.inverse());
120 btVector3 baseLinVal;
121 baseLinVal.deSerialize(mbd->m_baseLinearVelocity);
122 btVector3 baseAngVel;
123 baseAngVel.deSerialize(mbd->m_baseAngularVelocity);
124 mb->setBaseVel(baseLinVal);
125 mb->setBaseOmega(baseAngVel);
126
127 for (int i = 0; i < mbd->m_numLinks; i++)
128 {
129 mb->getLink(i).m_absFrameTotVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityTop);
130 mb->getLink(i).m_absFrameTotVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityBottom);
131 mb->getLink(i).m_absFrameLocVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityTop);
132 mb->getLink(i).m_absFrameLocVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityBottom);
133
134 switch (mbd->m_links[i].m_jointType)
135 {
137 {
138 break;
139 }
141 {
142 mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
143 mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
144 break;
145 }
147 {
148 mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
149 mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
150 break;
151 }
153 {
154 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]};
155 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]};
156 mb->setJointPosMultiDof(i, jointPos);
157 mb->setJointVelMultiDof(i, jointVel);
158
159 break;
160 }
162 {
163 break;
164 }
165 default:
166 {
167 }
168 }
169 }
170 mb->forwardKinematics(scratchQ, scratchM);
171 mb->updateCollisionObjectWorldTransforms(scratchQ, scratchM);
172}
173
174template <class T>
176{
177 bool isFixedBase = mbd->m_baseMass == 0;
178 bool canSleep = false;
179 btVector3 baseInertia;
180 baseInertia.deSerialize(mbd->m_baseInertia);
181 btMultiBody* mb = new btMultiBody(mbd->m_numLinks, mbd->m_baseMass, baseInertia, isFixedBase, canSleep);
182 mb->setHasSelfCollision(false);
183
184 btVector3 baseWorldPos;
185 baseWorldPos.deSerialize(mbd->m_baseWorldPosition);
186
187 btQuaternion baseWorldOrn;
188 baseWorldOrn.deSerialize(mbd->m_baseWorldOrientation);
189 mb->setBasePos(baseWorldPos);
190 mb->setWorldToBaseRot(baseWorldOrn.inverse());
191
192 m_data->m_mbMap.insert(mbd, mb);
193 for (int i = 0; i < mbd->m_numLinks; i++)
194 {
195 btVector3 localInertiaDiagonal;
196 localInertiaDiagonal.deSerialize(mbd->m_links[i].m_linkInertia);
197 btQuaternion parentRotToThis;
198 parentRotToThis.deSerialize(mbd->m_links[i].m_zeroRotParentToThis);
199 btVector3 parentComToThisPivotOffset;
200 parentComToThisPivotOffset.deSerialize(mbd->m_links[i].m_parentComToThisPivotOffset);
201 btVector3 thisPivotToThisComOffset;
202 thisPivotToThisComOffset.deSerialize(mbd->m_links[i].m_thisPivotToThisComOffset);
203
204 switch (mbd->m_links[i].m_jointType)
205 {
207 {
208 mb->setupFixed(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
209 parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset);
210 //search for the collider
211 //mbd->m_links[i].m_linkCollider
212 break;
213 }
215 {
216 btVector3 jointAxis;
217 jointAxis.deSerialize(mbd->m_links[i].m_jointAxisBottom[0]);
218 bool disableParentCollision = true; //todo
219 mb->setupPrismatic(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
220 parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
221 mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
222 mb->finalizeMultiDof();
223 mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
224 break;
225 }
227 {
228 btVector3 jointAxis;
229 jointAxis.deSerialize(mbd->m_links[i].m_jointAxisTop[0]);
230 bool disableParentCollision = true; //todo
231 mb->setupRevolute(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
232 parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
233 mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
234 mb->finalizeMultiDof();
235 mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
236 break;
237 }
239 {
240 btAssert(0);
241 bool disableParentCollision = true; //todo
242 mb->setupSpherical(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
243 parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
244 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]};
245 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]};
246 mb->setJointPosMultiDof(i, jointPos);
247 mb->finalizeMultiDof();
248 mb->setJointVelMultiDof(i, jointVel);
249
250 break;
251 }
253 {
254 btAssert(0);
255 break;
256 }
257 default:
258 {
259 btAssert(0);
260 }
261 }
262 }
263}
264
266{
267 bool result = false;
270
272 {
273 //check if the snapshot is valid for the existing world
274 //equal number of objects, # links etc
275 if ((bulletFile2->m_multiBodies.size() != m_data->m_mbDynamicsWorld->getNumMultibodies()))
276 {
277 printf("btMultiBodyWorldImporter::convertAllObjects error: expected %d multibodies, got %d.\n", m_data->m_mbDynamicsWorld->getNumMultibodies(), bulletFile2->m_multiBodies.size());
278 result = false;
279 return result;
280 }
281 result = true;
282
283 //convert all multibodies
284 if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
285 {
286 //for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
287 for (int i = bulletFile2->m_multiBodies.size() - 1; i >= 0; i--)
288 {
290 btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i);
291 if (mbd->m_numLinks != mb->getNumLinks())
292 {
293 printf("btMultiBodyWorldImporter::convertAllObjects error: mismatch in number of links in a body (expected %d, found %d).\n", mbd->m_numLinks, mb->getNumLinks() );
294 result = false;
295 return result;
296 } else
297 {
298 syncMultiBody(mbd, mb, m_data, scratchQ, scratchM);
299 }
300 }
301
302 for (int i = bulletFile2->m_rigidBodies.size() - 1; i >= 0; i--)
303 {
305 int foundRb = -1;
306 int uid = rbd->m_collisionObjectData.m_uniqueId;
307 for (int i = 0; i < m_data->m_mbDynamicsWorld->getNumCollisionObjects(); i++)
308 {
309 if (uid == m_data->m_mbDynamicsWorld->getCollisionObjectArray()[i]->getBroadphaseHandle()->m_uniqueId)
310 {
311 foundRb = i;
312 break;
313 }
314 }
315 if (foundRb >= 0)
316 {
317 btRigidBody* rb = btRigidBody::upcast(m_data->m_mbDynamicsWorld->getCollisionObjectArray()[foundRb]);
318 if (rb)
319 {
320 btTransform tr;
322 rb->setWorldTransform(tr);
323 btVector3 linVel, angVel;
326 rb->setLinearVelocity(linVel);
327 rb->setAngularVelocity(angVel);
328 }
329 else
330 {
331 printf("btMultiBodyWorldImporter::convertAllObjects error: cannot find btRigidBody with bodyUniqueId %d\n", uid);
332 result = false;
333 }
334 }
335 else
336 {
337 printf("Error in btMultiBodyWorldImporter::convertAllObjects: didn't find bodyUniqueId: %d\n", uid);
338 result = false;
339 }
340 }
341
342 //todo: check why body1 pointer is not properly deserialized
343 for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++)
344 {
346 {
347 void* ptr = bulletFile2->findLibPointer(manifoldData->m_body0);
348 if (ptr)
349 {
350 manifoldData->m_body0 = (btCollisionObjectDoubleData*)ptr;
351 }
352 }
353
354 {
355 void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1);
356 if (ptr)
357 {
358 manifoldData->m_body1 = (btCollisionObjectDoubleData*)ptr;
359 }
360 }
361 }
362
363 if (bulletFile2->m_contactManifolds.size())
364 {
366 }
367 }
368 else
369 {
370 //single precision version
371 //for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
372 for (int i = bulletFile2->m_multiBodies.size() - 1; i >= 0; i--)
373 {
375 btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i);
376 if (mbd->m_numLinks != mb->getNumLinks())
377 {
378 printf("btMultiBodyWorldImporter::convertAllObjects error: mismatch in number of links in a body (expected %d, found %d).\n", mbd->m_numLinks, mb->getNumLinks() );
379 result = false;
380 return result;
381 } else
382 {
383 syncMultiBody(mbd, mb, m_data, scratchQ, scratchM);
384 }
385 }
386
387 for (int i = bulletFile2->m_rigidBodies.size() - 1; i >= 0; i--)
388 {
390 int foundRb = -1;
391 int uid = rbd->m_collisionObjectData.m_uniqueId;
392 for (int i = 0; i < m_data->m_mbDynamicsWorld->getNumCollisionObjects(); i++)
393 {
394 if (uid == m_data->m_mbDynamicsWorld->getCollisionObjectArray()[i]->getBroadphaseHandle()->m_uniqueId)
395 {
396 foundRb = i;
397 break;
398 }
399 }
400 if (foundRb >= 0)
401 {
402 btRigidBody* rb = btRigidBody::upcast(m_data->m_mbDynamicsWorld->getCollisionObjectArray()[foundRb]);
403 if (rb)
404 {
405 btTransform tr;
407 rb->setWorldTransform(tr);
408 btVector3 linVel, angVel;
411 rb->setLinearVelocity(linVel);
412 rb->setAngularVelocity(angVel);
413 }
414 else
415 {
416 printf("btMultiBodyWorldImporter::convertAllObjects error: cannot find btRigidBody with bodyUniqueId %d\n", uid);
417 result = false;
418 }
419 }
420 else
421 {
422 printf("Error in btMultiBodyWorldImporter::convertAllObjects: didn't find bodyUniqueId: %d\n", uid);
423 result = false;
424 }
425 }
426
427 //todo: check why body1 pointer is not properly deserialized
428 for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++)
429 {
431 {
432 void* ptr = bulletFile2->findLibPointer(manifoldData->m_body0);
433 if (ptr)
434 {
435 manifoldData->m_body0 = (btCollisionObjectFloatData*)ptr;
436 }
437 }
438 {
439 void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1);
440 if (ptr)
441 {
442 manifoldData->m_body1 = (btCollisionObjectFloatData*)ptr;
443 }
444 }
445 }
446
447 if (bulletFile2->m_contactManifolds.size())
448 {
450 }
451 }
452 }
453 else
454 {
455 result = btBulletWorldImporter::convertAllObjects(bulletFile2);
456
457 //convert all multibodies
458 for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
459 {
460 if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
461 {
464 }
465 else
466 {
469 }
470 }
471
472 //forward kinematics, so that the link world transforms are valid, for collision detection
473 for (int i = 0; i < m_data->m_mbMap.size(); i++)
474 {
475 btMultiBody** ptr = m_data->m_mbMap.getAtIndex(i);
476 if (ptr)
477 {
478 btMultiBody* mb = *ptr;
479 mb->finalizeMultiDof();
480 btVector3 linvel = mb->getBaseVel();
481 btVector3 angvel = mb->getBaseOmega();
482 mb->forwardKinematics(scratchQ, scratchM);
483 }
484 }
485
486 //convert all multibody link colliders
487 for (int i = 0; i < bulletFile2->m_multiBodyLinkColliders.size(); i++)
488 {
489 if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
490 {
492
493 btMultiBody** ptr = m_data->m_mbMap[mblcd->m_multiBody];
494 if (ptr)
495 {
496 btMultiBody* multiBody = *ptr;
497
499 if (shapePtr && *shapePtr)
500 {
501 btTransform startTransform;
503 startTransform.deSerializeDouble(mblcd->m_colObjData.m_worldTransform);
504
505 btCollisionShape* shape = (btCollisionShape*)*shapePtr;
506 if (shape)
507 {
508 btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(multiBody, mblcd->m_link);
509 col->setCollisionShape(shape);
510 //btCollisionObject* body = createCollisionObject(startTransform,shape,mblcd->m_colObjData.m_name);
513 //m_bodyMap.insert(colObjData,body);
514 if (mblcd->m_link == -1)
515 {
516 col->setWorldTransform(multiBody->getBaseWorldTransform());
517 multiBody->setBaseCollider(col);
518 }
519 else
520 {
522 multiBody->getLink(mblcd->m_link).m_collider = col;
523 }
524 int mbLinkIndex = mblcd->m_link;
525
526 bool isDynamic = (mbLinkIndex < 0 && multiBody->hasFixedBase()) ? false : true;
527 int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
528 int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
529
530#if 0
531 int colGroup = 0, colMask = 0;
532 int collisionFlags = mblcd->m_colObjData.m_collisionFlags;
533 if (collisionFlags & URDF_HAS_COLLISION_GROUP)
534 {
535 collisionFilterGroup = colGroup;
536 }
537 if (collisionFlags & URDF_HAS_COLLISION_MASK)
538 {
539 collisionFilterMask = colMask;
540 }
541#endif
542 m_data->m_mbDynamicsWorld->addCollisionObject(col, collisionFilterGroup, collisionFilterMask);
543 }
544 }
545 else
546 {
547 printf("error: no shape found\n");
548 }
549#if 0
550 //base and fixed? -> static, otherwise flag as dynamic
551
552 world1->addCollisionObject(col, collisionFilterGroup, collisionFilterMask);
553#endif
554 }
555 }
556 }
557
558 for (int i = 0; i < m_data->m_mbMap.size(); i++)
559 {
560 btMultiBody** ptr = m_data->m_mbMap.getAtIndex(i);
561 if (ptr)
562 {
563 btMultiBody* mb = *ptr;
564 mb->finalizeMultiDof();
565
566 m_data->m_mbDynamicsWorld->addMultiBody(mb);
567 }
568 }
569 }
570 return result;
571}
btAlignedObjectArray< btPersistentManifold * > btManifoldArray
static btCollisionObjectDoubleData * getBody1FromContactManifold(btPersistentManifoldDoubleData *manifold)
void syncMultiBody(T *mbd, btMultiBody *mb, btMultiBodyWorldImporterInternalData *m_data, btAlignedObjectArray< btQuaternion > &scratchQ, btAlignedObjectArray< btVector3 > &scratchM)
void syncContactManifolds(T **contactManifolds, int numContactManifolds, btMultiBodyWorldImporterInternalData *m_data)
void convertMultiBody(T *mbd, btMultiBodyWorldImporterInternalData *m_data)
static btCollisionObjectDoubleData * getBody0FromContactManifold(btPersistentManifoldDoubleData *manifold)
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition btScalar.h:314
#define btAssert(x)
Definition btScalar.h:153
@ eRESTORE_EXISTING_OBJECTS
int getFlags() const
Definition bFile.h:122
void * findLibPointer(void *ptr)
Definition bFile.cpp:1440
btAlignedObjectArray< bStructHandle * > m_rigidBodies
btAlignedObjectArray< bStructHandle * > m_multiBodies
btAlignedObjectArray< bStructHandle * > m_contactManifolds
btAlignedObjectArray< bStructHandle * > m_multiBodyLinkColliders
The btAlignedObjectArray template class uses a subset of the stl::vector interface for its methods It...
int size() const
return the number of elements in the array
void clear()
clear the array, deallocated memory. Generally it is better to use array.resize(0),...
virtual btOverlappingPairCache * getOverlappingPairCache()=0
btBulletWorldImporter(btDynamicsWorld *world=0)
virtual bool convertAllObjects(bParse::btBulletFile *file)
virtual void getAllContactManifolds(btManifoldArray &manifoldArray)=0
void setRestitution(btScalar rest)
btBroadphaseProxy * getBroadphaseHandle()
virtual void setCollisionShape(btCollisionShape *collisionShape)
void setWorldTransform(const btTransform &worldTrans)
void setFriction(btScalar frict)
The btCollisionShape class provides an interface for collision shapes that can be shared among btColl...
virtual void updateAabbs()
btDispatcher * getDispatcher()
btDispatcherInfo & getDispatchInfo()
const btBroadphaseInterface * getBroadphase() const
virtual void computeOverlappingPairs()
the computeOverlappingPairs is usually already called by performDiscreteCollisionDetection (or stepSi...
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
virtual int getNumManifolds() const =0
virtual void dispatchAllCollisionPairs(btOverlappingPairCache *pairCache, const btDispatcherInfo &dispatchInfo, btDispatcher *dispatcher)=0
The btHashMap template class implements a generic and lightweight hashmap.
Definition btHashMap.h:220
void insert(const Key &key, const Value &value)
Definition btHashMap.h:264
The btMultiBodyDynamicsWorld adds Featherstone multi body dynamics to Bullet This implementation is s...
virtual void deleteAllData()
delete all memory collision shapes, rigid bodies, constraints etc.
virtual bool convertAllObjects(bParse::btBulletFile *bulletFile2)
struct btMultiBodyWorldImporterInternalData * m_data
btMultiBodyWorldImporter(class btMultiBodyDynamicsWorld *world)
void setupPrismatic(int i, btScalar mass, const btVector3 &inertia, int parent, const btQuaternion &rotParentToThis, const btVector3 &jointAxis, const btVector3 &parentComToThisPivotOffset, const btVector3 &thisPivotToThisComOffset, bool disableParentCollision)
void setJointVelMultiDof(int i, const double *qdot)
void finalizeMultiDof()
void setHasSelfCollision(bool hasSelfCollision)
void setBaseVel(const btVector3 &vel)
void setBaseOmega(const btVector3 &omega)
int getNumLinks() const
const btMultibodyLink & getLink(int index) const
btVector3 getBaseOmega() const
void setBasePos(const btVector3 &pos)
void setJointPosMultiDof(int i, const double *q)
void updateCollisionObjectWorldTransforms(btAlignedObjectArray< btQuaternion > &world_to_local, btAlignedObjectArray< btVector3 > &local_origin)
void setJointVel(int i, btScalar qdot)
bool hasFixedBase() const
void setupSpherical(int i, btScalar mass, const btVector3 &inertia, int parent, const btQuaternion &rotParentToThis, const btVector3 &parentComToThisPivotOffset, const btVector3 &thisPivotToThisComOffset, bool disableParentCollision=false)
void setJointPos(int i, btScalar q)
btTransform getBaseWorldTransform() const
void setupRevolute(int i, btScalar mass, const btVector3 &inertia, int parentIndex, const btQuaternion &rotParentToThis, const btVector3 &jointAxis, const btVector3 &parentComToThisPivotOffset, const btVector3 &thisPivotToThisComOffset, bool disableParentCollision=false)
void setupFixed(int i, btScalar mass, const btVector3 &inertia, int parent, const btQuaternion &rotParentToThis, const btVector3 &parentComToThisPivotOffset, const btVector3 &thisPivotToThisComOffset, bool deprecatedDisableParentCollision=true)
void setWorldToBaseRot(const btQuaternion &rot)
void forwardKinematics(btAlignedObjectArray< btQuaternion > &world_to_local, btAlignedObjectArray< btVector3 > &local_origin)
const btVector3 getBaseVel() const
void setBaseCollider(btMultiBodyLinkCollider *collider)
The btOverlappingPairCache provides an interface for overlapping pair management (add,...
virtual btBroadphasePairArray & getOverlappingPairArray()=0
virtual int getNumOverlappingPairs() const =0
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
const btCollisionObject * getBody0() const
const btCollisionObject * getBody1() const
void deSerialize(const struct btPersistentManifoldDoubleData *manifoldDataPtr)
void setNumContacts(int cachedPoints)
the setNumContacts API is usually not used, except when you gather/fill all contacts manually
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
btQuaternion inverse() const
Return the inverse of this quaternion.
void deSerialize(const struct btQuaternionFloatData &dataIn)
The btRigidBody is the main class for rigid body objects.
Definition btRigidBody.h:60
void setAngularVelocity(const btVector3 &ang_vel)
void setLinearVelocity(const btVector3 &lin_vel)
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don't store a rigidbody pointer but a rigidbody ...
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition btTransform.h:30
void deSerializeFloat(const struct btTransformFloatData &dataIn)
void deSerializeDouble(const struct btTransformDoubleData &dataIn)
btVector3 can be used to represent 3D points and vectors.
Definition btVector3.h:82
void deSerialize(const struct btVector3DoubleData &dataIn)
Definition btVector3.h:1330
void deSerializeFloat(const struct btVector3FloatData &dataIn)
Definition btVector3.h:1298
void deSerializeDouble(const struct btVector3DoubleData &dataIn)
Definition btVector3.h:1311
virtual void deleteAllData()
delete all memory collision shapes, rigid bodies, constraints etc.
btHashMap< btHashPtr, btCollisionShape * > m_shapeMap
@ FD_DOUBLE_PRECISION
Definition bFile.h:35
The btBroadphasePair class contains a pair of aabb-overlapping objects.
btCollisionAlgorithm * m_algorithm
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btTransformDoubleData m_worldTransform
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btTransformFloatData m_worldTransform
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btCollisionObjectDoubleData m_colObjData
btHashMap< btHashPtr, btMultiBody * > m_mbMap
btCollisionObjectDoubleData * m_body0
btCollisionObjectDoubleData * m_body1
btCollisionObjectFloatData * m_body1
btCollisionObjectFloatData * m_body0
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3DoubleData m_angularVelocity
btCollisionObjectDoubleData m_collisionObjectData
btVector3DoubleData m_linearVelocity
do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
btVector3FloatData m_angularVelocity
btCollisionObjectFloatData m_collisionObjectData
btVector3FloatData m_linearVelocity
btVector3DoubleData m_origin