Code-style consistency improvement:
Apply clang-format-all.sh using the _clang-format file through all the cpp/.h files. make sure not to apply it to certain serialization structures, since some parser expects the * as part of the name, instead of type. This commit contains no other changes aside from adding and applying clang-format-all.sh
This commit is contained in:
@@ -15,12 +15,11 @@ struct btMultiBodyWorldImporterInternalData
|
||||
};
|
||||
|
||||
btMultiBodyWorldImporter::btMultiBodyWorldImporter(btMultiBodyDynamicsWorld* world)
|
||||
:btBulletWorldImporter(world)
|
||||
: btBulletWorldImporter(world)
|
||||
{
|
||||
m_data = new btMultiBodyWorldImporterInternalData;
|
||||
m_data->m_mbDynamicsWorld = world;
|
||||
}
|
||||
|
||||
|
||||
btMultiBodyWorldImporter::~btMultiBodyWorldImporter()
|
||||
{
|
||||
@@ -32,7 +31,6 @@ void btMultiBodyWorldImporter::deleteAllData()
|
||||
btBulletWorldImporter::deleteAllData();
|
||||
}
|
||||
|
||||
|
||||
static btCollisionObjectDoubleData* getBody0FromContactManifold(btPersistentManifoldDoubleData* manifold)
|
||||
{
|
||||
return (btCollisionObjectDoubleData*)manifold->m_body0;
|
||||
@@ -50,8 +48,8 @@ static btCollisionObjectFloatData* getBody1FromContactManifold(btPersistentManif
|
||||
return (btCollisionObjectFloatData*)manifold->m_body1;
|
||||
}
|
||||
|
||||
|
||||
template<class T> void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMultiBodyWorldImporterInternalData* m_data)
|
||||
template <class T>
|
||||
void syncContactManifolds(T** contactManifolds, int numContactManifolds, btMultiBodyWorldImporterInternalData* m_data)
|
||||
{
|
||||
m_data->m_mbDynamicsWorld->updateAabbs();
|
||||
m_data->m_mbDynamicsWorld->computeOverlappingPairs();
|
||||
@@ -59,7 +57,6 @@ template<class T> void syncContactManifolds(T** contactManifolds, int numContact
|
||||
|
||||
btDispatcherInfo& dispatchInfo = m_data->m_mbDynamicsWorld->getDispatchInfo();
|
||||
|
||||
|
||||
if (dispatcher)
|
||||
{
|
||||
btOverlappingPairCache* pairCache = m_data->m_mbDynamicsWorld->getBroadphase()->getOverlappingPairCache();
|
||||
@@ -104,10 +101,10 @@ template<class T> void syncContactManifolds(T** contactManifolds, int numContact
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
template<class T> void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldImporterInternalData* m_data, btAlignedObjectArray<btQuaternion>& scratchQ, btAlignedObjectArray<btVector3>& scratchM)
|
||||
template <class T>
|
||||
void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldImporterInternalData* m_data, btAlignedObjectArray<btQuaternion>& scratchQ, btAlignedObjectArray<btVector3>& scratchM)
|
||||
{
|
||||
bool isFixedBase = mbd->m_baseMass == 0;
|
||||
bool canSleep = false;
|
||||
@@ -129,7 +126,6 @@ template<class T> void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldI
|
||||
|
||||
for (int i = 0; i < mbd->m_numLinks; i++)
|
||||
{
|
||||
|
||||
mb->getLink(i).m_absFrameTotVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityTop);
|
||||
mb->getLink(i).m_absFrameTotVelocity.m_bottomVec.deSerialize(mbd->m_links[i].m_absFrameTotVelocityBottom);
|
||||
mb->getLink(i).m_absFrameLocVelocity.m_topVec.deSerialize(mbd->m_links[i].m_absFrameLocVelocityTop);
|
||||
@@ -137,45 +133,46 @@ template<class T> void syncMultiBody(T* mbd, btMultiBody* mb, btMultiBodyWorldI
|
||||
|
||||
switch (mbd->m_links[i].m_jointType)
|
||||
{
|
||||
case btMultibodyLink::eFixed:
|
||||
{
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePrismatic:
|
||||
{
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eRevolute:
|
||||
{
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eSpherical:
|
||||
{
|
||||
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] };
|
||||
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] };
|
||||
mb->setJointPosMultiDof(i, jointPos);
|
||||
mb->setJointVelMultiDof(i, jointVel);
|
||||
case btMultibodyLink::eFixed:
|
||||
{
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePrismatic:
|
||||
{
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eRevolute:
|
||||
{
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eSpherical:
|
||||
{
|
||||
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]};
|
||||
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]};
|
||||
mb->setJointPosMultiDof(i, jointPos);
|
||||
mb->setJointVelMultiDof(i, jointVel);
|
||||
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePlanar:
|
||||
{
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
}
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePlanar:
|
||||
{
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
}
|
||||
}
|
||||
}
|
||||
mb->forwardKinematics(scratchQ, scratchM);
|
||||
mb->updateCollisionObjectWorldTransforms(scratchQ, scratchM);
|
||||
}
|
||||
|
||||
template<class T> void convertMultiBody(T* mbd, btMultiBodyWorldImporterInternalData* m_data)
|
||||
template <class T>
|
||||
void convertMultiBody(T* mbd, btMultiBodyWorldImporterInternalData* m_data)
|
||||
{
|
||||
bool isFixedBase = mbd->m_baseMass == 0;
|
||||
bool canSleep = false;
|
||||
@@ -206,71 +203,69 @@ template<class T> void convertMultiBody(T* mbd, btMultiBodyWorldImporterInterna
|
||||
|
||||
switch (mbd->m_links[i].m_jointType)
|
||||
{
|
||||
case btMultibodyLink::eFixed:
|
||||
{
|
||||
case btMultibodyLink::eFixed:
|
||||
{
|
||||
mb->setupFixed(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset);
|
||||
//search for the collider
|
||||
//mbd->m_links[i].m_linkCollider
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePrismatic:
|
||||
{
|
||||
btVector3 jointAxis;
|
||||
jointAxis.deSerialize(mbd->m_links[i].m_jointAxisBottom[0]);
|
||||
bool disableParentCollision = true; //todo
|
||||
mb->setupPrismatic(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eRevolute:
|
||||
{
|
||||
btVector3 jointAxis;
|
||||
jointAxis.deSerialize(mbd->m_links[i].m_jointAxisTop[0]);
|
||||
bool disableParentCollision = true; //todo
|
||||
mb->setupRevolute(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eSpherical:
|
||||
{
|
||||
btAssert(0);
|
||||
bool disableParentCollision = true; //todo
|
||||
mb->setupSpherical(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
|
||||
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]};
|
||||
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]};
|
||||
mb->setJointPosMultiDof(i, jointPos);
|
||||
mb->setJointVelMultiDof(i, jointVel);
|
||||
|
||||
|
||||
mb->setupFixed(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset);
|
||||
//search for the collider
|
||||
//mbd->m_links[i].m_linkCollider
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePrismatic:
|
||||
{
|
||||
btVector3 jointAxis;
|
||||
jointAxis.deSerialize(mbd->m_links[i].m_jointAxisBottom[0]);
|
||||
bool disableParentCollision = true;//todo
|
||||
mb->setupPrismatic(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eRevolute:
|
||||
{
|
||||
btVector3 jointAxis;
|
||||
jointAxis.deSerialize(mbd->m_links[i].m_jointAxisTop[0]);
|
||||
bool disableParentCollision = true;//todo
|
||||
mb->setupRevolute(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, jointAxis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
|
||||
mb->setJointPos(i, mbd->m_links[i].m_jointPos[0]);
|
||||
mb->setJointVel(i, mbd->m_links[i].m_jointVel[0]);
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::eSpherical:
|
||||
{
|
||||
btAssert(0);
|
||||
bool disableParentCollision = true;//todo
|
||||
mb->setupSpherical(i, mbd->m_links[i].m_linkMass, localInertiaDiagonal, mbd->m_links[i].m_parentIndex,
|
||||
parentRotToThis, parentComToThisPivotOffset, thisPivotToThisComOffset, disableParentCollision);
|
||||
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] };
|
||||
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] };
|
||||
mb->setJointPosMultiDof(i, jointPos);
|
||||
mb->setJointVelMultiDof(i, jointVel);
|
||||
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePlanar:
|
||||
{
|
||||
btAssert(0);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
btAssert(0);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case btMultibodyLink::ePlanar:
|
||||
{
|
||||
btAssert(0);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
btAssert(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile2)
|
||||
bool btMultiBodyWorldImporter::convertAllObjects(bParse::btBulletFile* bulletFile2)
|
||||
{
|
||||
bool result = false;
|
||||
btAlignedObjectArray<btQuaternion> scratchQ;
|
||||
btAlignedObjectArray<btVector3> scratchM;
|
||||
|
||||
if (m_importerFlags&eRESTORE_EXISTING_OBJECTS)
|
||||
if (m_importerFlags & eRESTORE_EXISTING_OBJECTS)
|
||||
{
|
||||
//check if the snapshot is valid for the existing world
|
||||
//equal number of objects, # links etc
|
||||
@@ -284,7 +279,6 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
//convert all multibodies
|
||||
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--)
|
||||
{
|
||||
@@ -352,7 +346,6 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (bulletFile2->m_contactManifolds.size())
|
||||
{
|
||||
syncContactManifolds((btPersistentManifoldDoubleData**)&bulletFile2->m_contactManifolds[0], bulletFile2->m_contactManifolds.size(), m_data);
|
||||
@@ -389,23 +382,19 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (bulletFile2->m_contactManifolds.size())
|
||||
{
|
||||
syncContactManifolds((btPersistentManifoldFloatData**)&bulletFile2->m_contactManifolds[0], bulletFile2->m_contactManifolds.size(), m_data);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
result = btBulletWorldImporter::convertAllObjects(bulletFile2);
|
||||
|
||||
|
||||
//convert all multibodies
|
||||
for (int i = 0; i < bulletFile2->m_multiBodies.size(); i++)
|
||||
{
|
||||
|
||||
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
|
||||
{
|
||||
btMultiBodyDoubleData* mbd = (btMultiBodyDoubleData*)bulletFile2->m_multiBodies[i];
|
||||
@@ -421,7 +410,7 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
//forward kinematics, so that the link world transforms are valid, for collision detection
|
||||
for (int i = 0; i < m_data->m_mbMap.size(); i++)
|
||||
{
|
||||
btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i);
|
||||
btMultiBody** ptr = m_data->m_mbMap.getAtIndex(i);
|
||||
if (ptr)
|
||||
{
|
||||
btMultiBody* mb = *ptr;
|
||||
@@ -444,7 +433,6 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
{
|
||||
btMultiBody* multiBody = *ptr;
|
||||
|
||||
|
||||
btCollisionShape** shapePtr = m_shapeMap.find(mblcd->m_colObjData.m_collisionShape);
|
||||
if (shapePtr && *shapePtr)
|
||||
{
|
||||
@@ -491,7 +479,6 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
#endif
|
||||
m_data->m_mbDynamicsWorld->addCollisionObject(col, collisionFilterGroup, collisionFilterMask);
|
||||
}
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -503,13 +490,12 @@ bool btMultiBodyWorldImporter::convertAllObjects( bParse::btBulletFile* bulletF
|
||||
world1->addCollisionObject(col, collisionFilterGroup, collisionFilterMask);
|
||||
#endif
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0; i < m_data->m_mbMap.size(); i++)
|
||||
{
|
||||
btMultiBody**ptr = m_data->m_mbMap.getAtIndex(i);
|
||||
btMultiBody** ptr = m_data->m_mbMap.getAtIndex(i);
|
||||
if (ptr)
|
||||
{
|
||||
btMultiBody* mb = *ptr;
|
||||
|
||||
Reference in New Issue
Block a user