made some progress in saving and restoring the state during the simulation, with identical results.
Option to de/serialize btPersistentContactManifolds and fix lossy conversion during btMultiBody de/serialization of base world transform (serialize the quaternion, not the converted 3x3 matrix) There are still several caches not taken into account, and btMultiBody links/constraints are not deserialized yet etc. See examples\pybullet\examples\saveRestoreState.py for an example.
This commit is contained in:
@@ -63,6 +63,8 @@ typedef struct bInvalidHandle {
|
||||
class btCapsuleShapeData;
|
||||
class btTriangleInfoData;
|
||||
class btTriangleInfoMapData;
|
||||
class btPersistentManifoldDoubleData;
|
||||
class btPersistentManifoldFloatData;
|
||||
class btGImpactMeshShapeData;
|
||||
class btConvexHullShapeData;
|
||||
class btCollisionObjectDoubleData;
|
||||
@@ -514,6 +516,96 @@ typedef struct bInvalidHandle {
|
||||
};
|
||||
|
||||
|
||||
// -------------------------------------------------- //
|
||||
class btPersistentManifoldDoubleData
|
||||
{
|
||||
public:
|
||||
btVector3DoubleData m_pointCacheLocalPointA[4];
|
||||
btVector3DoubleData m_pointCacheLocalPointB[4];
|
||||
btVector3DoubleData m_pointCachePositionWorldOnA[4];
|
||||
btVector3DoubleData m_pointCachePositionWorldOnB[4];
|
||||
btVector3DoubleData m_pointCacheNormalWorldOnB[4];
|
||||
btVector3DoubleData m_pointCacheLateralFrictionDir1[4];
|
||||
btVector3DoubleData m_pointCacheLateralFrictionDir2[4];
|
||||
double m_pointCacheDistance[4];
|
||||
double m_pointCacheAppliedImpulse[4];
|
||||
double m_pointCacheCombinedFriction[4];
|
||||
double m_pointCacheCombinedRollingFriction[4];
|
||||
double m_pointCacheCombinedSpinningFriction[4];
|
||||
double m_pointCacheCombinedRestitution[4];
|
||||
int m_pointCachePartId0[4];
|
||||
int m_pointCachePartId1[4];
|
||||
int m_pointCacheIndex0[4];
|
||||
int m_pointCacheIndex1[4];
|
||||
int m_pointCacheContactPointFlags[4];
|
||||
double m_pointCacheAppliedImpulseLateral1[4];
|
||||
double m_pointCacheAppliedImpulseLateral2[4];
|
||||
double m_pointCacheContactMotion1[4];
|
||||
double m_pointCacheContactMotion2[4];
|
||||
double m_pointCacheContactCFM[4];
|
||||
double m_pointCacheCombinedContactStiffness1[4];
|
||||
double m_pointCacheContactERP[4];
|
||||
double m_pointCacheCombinedContactDamping1[4];
|
||||
double m_pointCacheFrictionCFM[4];
|
||||
int m_pointCacheLifeTime[4];
|
||||
int m_numCachedPoints;
|
||||
int m_companionIdA;
|
||||
int m_companionIdB;
|
||||
int m_index1a;
|
||||
int m_objectType;
|
||||
double m_contactBreakingThreshold;
|
||||
double m_contactProcessingThreshold;
|
||||
int m_padding;
|
||||
void *m_body0;
|
||||
void *m_body1;
|
||||
};
|
||||
|
||||
|
||||
// -------------------------------------------------- //
|
||||
class btPersistentManifoldFloatData
|
||||
{
|
||||
public:
|
||||
btVector3FloatData m_pointCacheLocalPointA[4];
|
||||
btVector3FloatData m_pointCacheLocalPointB[4];
|
||||
btVector3FloatData m_pointCachePositionWorldOnA[4];
|
||||
btVector3FloatData m_pointCachePositionWorldOnB[4];
|
||||
btVector3FloatData m_pointCacheNormalWorldOnB[4];
|
||||
btVector3FloatData m_pointCacheLateralFrictionDir1;
|
||||
btVector3FloatData m_pointCacheLateralFrictionDir2;
|
||||
float m_pointCacheDistance[4];
|
||||
float m_pointCacheAppliedImpulse[4];
|
||||
float m_pointCacheCombinedFriction[4];
|
||||
float m_pointCacheCombinedRollingFriction[4];
|
||||
float m_pointCacheCombinedSpinningFriction[4];
|
||||
float m_pointCacheCombinedRestitution[4];
|
||||
int m_pointCachePartId0[4];
|
||||
int m_pointCachePartId1[4];
|
||||
int m_pointCacheIndex0[4];
|
||||
int m_pointCacheIndex1[4];
|
||||
int m_pointCacheContactPointFlags[4];
|
||||
float m_pointCacheAppliedImpulseLateral1[4];
|
||||
float m_pointCacheAppliedImpulseLateral2[4];
|
||||
float m_pointCacheContactMotion1[4];
|
||||
float m_pointCacheContactMotion2[4];
|
||||
float m_pointCacheContactCFM[4];
|
||||
float m_pointCacheCombinedContactStiffness1[4];
|
||||
float m_pointCacheContactERP[4];
|
||||
float m_pointCacheCombinedContactDamping1[4];
|
||||
float m_pointCacheFrictionCFM[4];
|
||||
int m_pointCacheLifeTime[4];
|
||||
int m_numCachedPoints;
|
||||
int m_companionIdA;
|
||||
int m_companionIdB;
|
||||
int m_index1a;
|
||||
int m_objectType;
|
||||
float m_contactBreakingThreshold;
|
||||
float m_contactProcessingThreshold;
|
||||
int m_padding;
|
||||
void *m_body0;
|
||||
void *m_body1;
|
||||
};
|
||||
|
||||
|
||||
// -------------------------------------------------- //
|
||||
class btGImpactMeshShapeData
|
||||
{
|
||||
@@ -568,7 +660,9 @@ typedef struct bInvalidHandle {
|
||||
int m_activationState1;
|
||||
int m_internalType;
|
||||
int m_checkCollideWith;
|
||||
char m_padding[4];
|
||||
int m_collisionFilterGroup;
|
||||
int m_collisionFilterMask;
|
||||
int m_uniqueId;
|
||||
};
|
||||
|
||||
|
||||
@@ -602,7 +696,9 @@ typedef struct bInvalidHandle {
|
||||
int m_activationState1;
|
||||
int m_internalType;
|
||||
int m_checkCollideWith;
|
||||
char m_padding[4];
|
||||
int m_collisionFilterGroup;
|
||||
int m_collisionFilterMask;
|
||||
int m_uniqueId;
|
||||
};
|
||||
|
||||
|
||||
@@ -1416,15 +1512,17 @@ typedef struct bInvalidHandle {
|
||||
class btMultiBodyDoubleData
|
||||
{
|
||||
public:
|
||||
btTransformDoubleData m_baseWorldTransform;
|
||||
btVector3DoubleData m_baseWorldPosition;
|
||||
btQuaternionDoubleData m_baseWorldOrientation;
|
||||
btVector3DoubleData m_baseLinearVelocity;
|
||||
btVector3DoubleData m_baseAngularVelocity;
|
||||
btVector3DoubleData m_baseInertia;
|
||||
double m_baseMass;
|
||||
int m_numLinks;
|
||||
char m_padding[4];
|
||||
char *m_baseName;
|
||||
btMultiBodyLinkDoubleData *m_links;
|
||||
btCollisionObjectDoubleData *m_baseCollider;
|
||||
char *m_paddingPtr;
|
||||
int m_numLinks;
|
||||
char m_padding[4];
|
||||
};
|
||||
|
||||
|
||||
@@ -1432,13 +1530,16 @@ typedef struct bInvalidHandle {
|
||||
class btMultiBodyFloatData
|
||||
{
|
||||
public:
|
||||
char *m_baseName;
|
||||
btMultiBodyLinkFloatData *m_links;
|
||||
btCollisionObjectFloatData *m_baseCollider;
|
||||
btTransformFloatData m_baseWorldTransform;
|
||||
btVector3FloatData m_baseWorldPosition;
|
||||
btQuaternionFloatData m_baseWorldOrientation;
|
||||
btVector3FloatData m_baseLinearVelocity;
|
||||
btVector3FloatData m_baseAngularVelocity;
|
||||
btVector3FloatData m_baseInertia;
|
||||
float m_baseMass;
|
||||
int m_numLinks;
|
||||
char *m_baseName;
|
||||
btMultiBodyLinkFloatData *m_links;
|
||||
btCollisionObjectFloatData *m_baseCollider;
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -176,6 +176,10 @@ void btBulletFile::parseData()
|
||||
// listID->push_back((bStructHandle*)id);
|
||||
}
|
||||
|
||||
if (dataChunk.code == BT_CONTACTMANIFOLD_CODE)
|
||||
{
|
||||
m_contactManifolds.push_back((bStructHandle*)id);
|
||||
}
|
||||
if (dataChunk.code == BT_MULTIBODY_CODE)
|
||||
{
|
||||
m_multiBodies.push_back((bStructHandle*)id);
|
||||
|
||||
@@ -59,6 +59,8 @@ namespace bParse {
|
||||
|
||||
btAlignedObjectArray<bStructHandle*> m_dynamicsWorldInfo;
|
||||
|
||||
btAlignedObjectArray<bStructHandle*> m_contactManifolds;
|
||||
|
||||
btAlignedObjectArray<char*> m_dataBlocks;
|
||||
btBulletFile();
|
||||
|
||||
|
||||
@@ -52,10 +52,11 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
result = true;
|
||||
|
||||
//convert all multibodies
|
||||
for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
|
||||
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
|
||||
{
|
||||
|
||||
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
|
||||
//for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
|
||||
for (int i = bulletFile2->m_multiBodies.size()-1; i >=0; i--)
|
||||
{
|
||||
btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*)bulletFile2->m_multiBodies[i];
|
||||
bool isFixedBase = mbd->m_baseMass == 0;
|
||||
@@ -63,9 +64,20 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
btVector3 baseInertia;
|
||||
baseInertia.deSerializeDouble(mbd->m_baseInertia);
|
||||
|
||||
btTransform tr; tr.deSerializeDouble(mbd->m_baseWorldTransform);
|
||||
btMultiBody* mb = m_data->m_mbDynamicsWorld->getMultiBody(i);
|
||||
mb->setBaseWorldTransform(tr);
|
||||
btVector3 baseWorldPos;
|
||||
baseWorldPos.deSerializeDouble(mbd->m_baseWorldPosition);
|
||||
mb->setBasePos(baseWorldPos);
|
||||
btQuaternion baseWorldRot;
|
||||
baseWorldRot.deSerializeDouble(mbd->m_baseWorldOrientation);
|
||||
mb->setWorldToBaseRot(baseWorldRot.inverse());
|
||||
btVector3 baseLinVal;
|
||||
baseLinVal.deSerializeDouble(mbd->m_baseLinearVelocity);
|
||||
btVector3 baseAngVel;
|
||||
baseAngVel.deSerializeDouble(mbd->m_baseAngularVelocity);
|
||||
mb->setBaseVel(baseLinVal);
|
||||
mb->setBaseOmega(baseAngVel);
|
||||
|
||||
for (int i = 0; i < mbd->m_numLinks; i++)
|
||||
{
|
||||
}
|
||||
@@ -74,6 +86,74 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
mb->forwardKinematics(scratchQ, scratchM);
|
||||
mb->updateCollisionObjectWorldTransforms(scratchQ, scratchM);
|
||||
}
|
||||
|
||||
//todo: check why body1 pointer is not properly deserialized
|
||||
for (int i = 0; i < bulletFile2->m_contactManifolds.size(); i++)
|
||||
{
|
||||
btPersistentManifoldDoubleData* manifoldData = (btPersistentManifoldDoubleData*)bulletFile2->m_contactManifolds[i];
|
||||
void* ptr = bulletFile2->findLibPointer(manifoldData->m_body1);
|
||||
if (ptr)
|
||||
{
|
||||
manifoldData->m_body1 = ptr;
|
||||
btCollisionObjectDoubleData* cdd = (btCollisionObjectDoubleData*)ptr;
|
||||
}
|
||||
}
|
||||
|
||||
btDispatcherInfo& dispatchInfo = m_data->m_mbDynamicsWorld->getDispatchInfo();
|
||||
|
||||
{
|
||||
m_data->m_mbDynamicsWorld->updateAabbs();
|
||||
m_data->m_mbDynamicsWorld->computeOverlappingPairs();
|
||||
btDispatcher* dispatcher = m_data->m_mbDynamicsWorld->getDispatcher();
|
||||
|
||||
if (dispatcher)
|
||||
{
|
||||
btOverlappingPairCache* pairCache = m_data->m_mbDynamicsWorld->getBroadphase()->getOverlappingPairCache();
|
||||
if (dispatcher)
|
||||
{
|
||||
dispatcher->dispatchAllCollisionPairs(pairCache, dispatchInfo, dispatcher);
|
||||
}
|
||||
int numExistingManifolds = m_data->m_mbDynamicsWorld->getDispatcher()->getNumManifolds();
|
||||
btManifoldArray manifoldArray;
|
||||
for (int i = 0; i < pairCache->getNumOverlappingPairs(); i++)
|
||||
{
|
||||
btBroadphasePair& pair = pairCache->getOverlappingPairArray()[i];
|
||||
if (pair.m_algorithm)
|
||||
{
|
||||
pair.m_algorithm->getAllContactManifolds(manifoldArray);
|
||||
//for each existing manifold, search a matching manifoldData and reconstruct
|
||||
for (int m = 0; m < manifoldArray.size(); m++)
|
||||
{
|
||||
btPersistentManifold* existingManifold = manifoldArray[m];
|
||||
int uid0 = existingManifold->getBody0()->getBroadphaseHandle()->m_uniqueId;
|
||||
int uid1 = existingManifold->getBody1()->getBroadphaseHandle()->m_uniqueId;
|
||||
int matchingManifoldIndex = -1;
|
||||
for (int q= 0; q < bulletFile2->m_contactManifolds.size(); q++)
|
||||
{
|
||||
btPersistentManifoldDoubleData* manifoldData = (btPersistentManifoldDoubleData*)bulletFile2->m_contactManifolds[q];
|
||||
btCollisionObjectDoubleData* cdd0 = (btCollisionObjectDoubleData*)manifoldData->m_body0;
|
||||
btCollisionObjectDoubleData* cdd1 = (btCollisionObjectDoubleData*)manifoldData->m_body1;
|
||||
if (uid0 == cdd0->m_uniqueId && uid1 == cdd1->m_uniqueId)
|
||||
{
|
||||
matchingManifoldIndex = q;
|
||||
}
|
||||
}
|
||||
if (matchingManifoldIndex >= 0)
|
||||
{
|
||||
btPersistentManifoldDoubleData* manifoldData = (btPersistentManifoldDoubleData*)bulletFile2->m_contactManifolds[matchingManifoldIndex];
|
||||
existingManifold->deSerializeDouble(manifoldData);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Issue: cannot find maching contact manifold (%d, %d), may cause issues in determinism.\n", uid0, uid1);
|
||||
}
|
||||
|
||||
manifoldArray.clear();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
@@ -94,8 +174,14 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
baseInertia.deSerializeDouble(mbd->m_baseInertia);
|
||||
btMultiBody* mb = new btMultiBody(mbd->m_numLinks, mbd->m_baseMass, baseInertia, isFixedBase, canSleep);
|
||||
mb->setHasSelfCollision(false);
|
||||
btTransform tr; tr.deSerializeDouble(mbd->m_baseWorldTransform);
|
||||
mb->setBaseWorldTransform(tr);
|
||||
|
||||
btVector3 baseWorldPos;
|
||||
baseWorldPos.deSerializeDouble(mbd->m_baseWorldPosition);
|
||||
|
||||
btQuaternion baseWorldOrn;
|
||||
baseWorldOrn.deSerializeDouble(mbd->m_baseWorldOrientation);
|
||||
mb->setBasePos(baseWorldPos);
|
||||
mb->setWorldToBaseRot(baseWorldOrn.inverse());
|
||||
|
||||
m_data->m_mbMap.insert(mbd, mb);
|
||||
for (int i = 0; i < mbd->m_numLinks; i++)
|
||||
|
||||
@@ -132,6 +132,7 @@ typedef unsigned __int64 uint64_t;
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btCapsuleShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btTriangleInfoMap.h"
|
||||
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
|
||||
#include "BulletCollision/Gimpact/btGImpactShape.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
@@ -181,6 +182,7 @@ char *includefiles[] = {
|
||||
"../../../src/BulletCollision/CollisionShapes/btConeShape.h",
|
||||
"../../../src/BulletCollision/CollisionShapes/btCapsuleShape.h",
|
||||
"../../../src/BulletCollision/CollisionShapes/btTriangleInfoMap.h",
|
||||
"../../../src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h",
|
||||
"../../../src/BulletCollision/Gimpact/btGImpactShape.h",
|
||||
"../../../src/BulletCollision/CollisionShapes/btConvexHullShape.h",
|
||||
"../../../src/BulletCollision/CollisionDispatch/btCollisionObject.h",
|
||||
|
||||
Reference in New Issue
Block a user