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:
erwincoumans
2018-09-23 14:17:31 -07:00
parent b73b05e9fb
commit ab8f16961e
1773 changed files with 1081087 additions and 474249 deletions

View File

@@ -13,7 +13,6 @@ subject to the following restrictions:
3. This notice may not be removed or altered from any source distribution.
*/
#include "btBulletWorldImporter.h"
#include "../BulletFileLoader/btBulletFile.h"
@@ -22,14 +21,13 @@ subject to the following restrictions:
#include "BulletCollision/Gimpact/btGImpactShape.h"
#endif
//#define USE_INTERNAL_EDGE_UTILITY
#ifdef USE_INTERNAL_EDGE_UTILITY
#include "BulletCollision/CollisionDispatch/btInternalEdgeUtility.h"
#endif //USE_INTERNAL_EDGE_UTILITY
#endif //USE_INTERNAL_EDGE_UTILITY
btBulletWorldImporter::btBulletWorldImporter(btDynamicsWorld* world)
:btWorldImporter(world)
: btWorldImporter(world)
{
}
@@ -37,12 +35,10 @@ btBulletWorldImporter::~btBulletWorldImporter()
{
}
bool btBulletWorldImporter::loadFile( const char* fileName, const char* preSwapFilenameOut)
bool btBulletWorldImporter::loadFile(const char* fileName, const char* preSwapFilenameOut)
{
bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(fileName);
bool result = loadFileFromMemory(bulletFile2);
//now you could save the file in 'native' format using
//bulletFile2->writeFile("native.bullet");
@@ -53,19 +49,15 @@ bool btBulletWorldImporter::loadFile( const char* fileName, const char* preSwapF
bulletFile2->preSwap();
bulletFile2->writeFile(preSwapFilenameOut);
}
}
delete bulletFile2;
return result;
return result;
}
bool btBulletWorldImporter::loadFileFromMemory( char* memoryBuffer, int len)
bool btBulletWorldImporter::loadFileFromMemory(char* memoryBuffer, int len)
{
bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(memoryBuffer,len);
bParse::btBulletFile* bulletFile2 = new bParse::btBulletFile(memoryBuffer, len);
bool result = loadFileFromMemory(bulletFile2);
@@ -74,36 +66,31 @@ bool btBulletWorldImporter::loadFileFromMemory( char* memoryBuffer, int len)
return result;
}
bool btBulletWorldImporter::loadFileFromMemory( bParse::btBulletFile* bulletFile2)
bool btBulletWorldImporter::loadFileFromMemory(bParse::btBulletFile* bulletFile2)
{
bool ok = (bulletFile2->getFlags()& bParse::FD_OK)!=0;
bool ok = (bulletFile2->getFlags() & bParse::FD_OK) != 0;
if (ok)
bulletFile2->parse(m_verboseMode);
else
else
return false;
if (m_verboseMode & bParse::FD_VERBOSE_DUMP_CHUNKS)
{
bulletFile2->dumpChunks(bulletFile2->getFileDNA());
}
return convertAllObjects(bulletFile2);
}
bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile2)
bool btBulletWorldImporter::convertAllObjects(bParse::btBulletFile* bulletFile2)
{
m_shapeMap.clear();
m_bodyMap.clear();
int i;
for (i=0;i<bulletFile2->m_bvhs.size();i++)
for (i = 0; i < bulletFile2->m_bvhs.size(); i++)
{
btOptimizedBvh* bvh = createOptimizedBvh();
@@ -111,41 +98,34 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
{
btQuantizedBvhDoubleData* bvhData = (btQuantizedBvhDoubleData*)bulletFile2->m_bvhs[i];
bvh->deSerializeDouble(*bvhData);
} else
}
else
{
btQuantizedBvhFloatData* bvhData = (btQuantizedBvhFloatData*)bulletFile2->m_bvhs[i];
bvh->deSerializeFloat(*bvhData);
}
m_bvhMap.insert(bulletFile2->m_bvhs[i],bvh);
m_bvhMap.insert(bulletFile2->m_bvhs[i], bvh);
}
for (i=0;i<bulletFile2->m_collisionShapes.size();i++)
for (i = 0; i < bulletFile2->m_collisionShapes.size(); i++)
{
btCollisionShapeData* shapeData = (btCollisionShapeData*)bulletFile2->m_collisionShapes[i];
btCollisionShape* shape = convertCollisionShape(shapeData);
if (shape)
{
// printf("shapeMap.insert(%x,%x)\n",shapeData,shape);
m_shapeMap.insert(shapeData,shape);
// printf("shapeMap.insert(%x,%x)\n",shapeData,shape);
m_shapeMap.insert(shapeData, shape);
}
if (shape&& shapeData->m_name)
if (shape && shapeData->m_name)
{
char* newname = duplicateName(shapeData->m_name);
m_objectNameMap.insert(shape,newname);
m_nameShapeMap.insert(newname,shape);
m_objectNameMap.insert(shape, newname);
m_nameShapeMap.insert(newname, shape);
}
}
for (int i=0;i<bulletFile2->m_dynamicsWorldInfo.size();i++)
for (int i = 0; i < bulletFile2->m_dynamicsWorldInfo.size(); i++)
{
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
{
@@ -169,21 +149,22 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
solverInfo.m_globalCfm = btScalar(solverInfoData->m_solverInfo.m_globalCfm);
solverInfo.m_splitImpulsePenetrationThreshold = btScalar(solverInfoData->m_solverInfo.m_splitImpulsePenetrationThreshold);
solverInfo.m_splitImpulseTurnErp = btScalar(solverInfoData->m_solverInfo.m_splitImpulseTurnErp);
solverInfo.m_linearSlop = btScalar(solverInfoData->m_solverInfo.m_linearSlop);
solverInfo.m_warmstartingFactor = btScalar(solverInfoData->m_solverInfo.m_warmstartingFactor);
solverInfo.m_maxGyroscopicForce = btScalar(solverInfoData->m_solverInfo.m_maxGyroscopicForce);
solverInfo.m_singleAxisRollingFrictionThreshold = btScalar(solverInfoData->m_solverInfo.m_singleAxisRollingFrictionThreshold);
solverInfo.m_numIterations = solverInfoData->m_solverInfo.m_numIterations;
solverInfo.m_solverMode = solverInfoData->m_solverInfo.m_solverMode;
solverInfo.m_restingContactRestitutionThreshold = solverInfoData->m_solverInfo.m_restingContactRestitutionThreshold;
solverInfo.m_minimumSolverBatchSize = solverInfoData->m_solverInfo.m_minimumSolverBatchSize;
solverInfo.m_splitImpulse = solverInfoData->m_solverInfo.m_splitImpulse;
setDynamicsWorldInfo(gravity,solverInfo);
} else
setDynamicsWorldInfo(gravity, solverInfo);
}
else
{
btDynamicsWorldFloatData* solverInfoData = (btDynamicsWorldFloatData*)bulletFile2->m_dynamicsWorldInfo[i];
btContactSolverInfo solverInfo;
@@ -205,40 +186,38 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
solverInfo.m_globalCfm = solverInfoData->m_solverInfo.m_globalCfm;
solverInfo.m_splitImpulsePenetrationThreshold = solverInfoData->m_solverInfo.m_splitImpulsePenetrationThreshold;
solverInfo.m_splitImpulseTurnErp = solverInfoData->m_solverInfo.m_splitImpulseTurnErp;
solverInfo.m_linearSlop = solverInfoData->m_solverInfo.m_linearSlop;
solverInfo.m_warmstartingFactor = solverInfoData->m_solverInfo.m_warmstartingFactor;
solverInfo.m_maxGyroscopicForce = solverInfoData->m_solverInfo.m_maxGyroscopicForce;
solverInfo.m_singleAxisRollingFrictionThreshold = solverInfoData->m_solverInfo.m_singleAxisRollingFrictionThreshold;
solverInfo.m_numIterations = solverInfoData->m_solverInfo.m_numIterations;
solverInfo.m_solverMode = solverInfoData->m_solverInfo.m_solverMode;
solverInfo.m_restingContactRestitutionThreshold = solverInfoData->m_solverInfo.m_restingContactRestitutionThreshold;
solverInfo.m_minimumSolverBatchSize = solverInfoData->m_solverInfo.m_minimumSolverBatchSize;
solverInfo.m_splitImpulse = solverInfoData->m_solverInfo.m_splitImpulse;
setDynamicsWorldInfo(gravity,solverInfo);
setDynamicsWorldInfo(gravity, solverInfo);
}
}
for (i=0;i<bulletFile2->m_rigidBodies.size();i++)
for (i = 0; i < bulletFile2->m_rigidBodies.size(); i++)
{
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
{
btRigidBodyDoubleData* colObjData = (btRigidBodyDoubleData*)bulletFile2->m_rigidBodies[i];
convertRigidBodyDouble(colObjData);
} else
}
else
{
btRigidBodyFloatData* colObjData = (btRigidBodyFloatData*)bulletFile2->m_rigidBodies[i];
convertRigidBodyFloat(colObjData);
}
}
for (i=0;i<bulletFile2->m_collisionObjects.size();i++)
for (i = 0; i < bulletFile2->m_collisionObjects.size(); i++)
{
if (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)
{
@@ -249,29 +228,30 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
btTransform startTransform;
colObjData->m_worldTransform.m_origin.m_floats[3] = 0.f;
startTransform.deSerializeDouble(colObjData->m_worldTransform);
btCollisionShape* shape = (btCollisionShape*)*shapePtr;
btCollisionObject* body = createCollisionObject(startTransform,shape,colObjData->m_name);
btCollisionObject* body = createCollisionObject(startTransform, shape, colObjData->m_name);
body->setFriction(btScalar(colObjData->m_friction));
body->setRestitution(btScalar(colObjData->m_restitution));
#ifdef USE_INTERNAL_EDGE_UTILITY
if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE)
{
btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*)shape;
if (trimesh->getTriangleInfoMap())
{
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
}
}
#endif //USE_INTERNAL_EDGE_UTILITY
m_bodyMap.insert(colObjData,body);
} else
#endif //USE_INTERNAL_EDGE_UTILITY
m_bodyMap.insert(colObjData, body);
}
else
{
printf("error: no shape found\n");
}
} else
}
else
{
btCollisionObjectFloatData* colObjData = (btCollisionObjectFloatData*)bulletFile2->m_collisionObjects[i];
btCollisionShape** shapePtr = m_shapeMap.find(colObjData->m_collisionShape);
@@ -280,9 +260,9 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
btTransform startTransform;
colObjData->m_worldTransform.m_origin.m_floats[3] = 0.f;
startTransform.deSerializeFloat(colObjData->m_worldTransform);
btCollisionShape* shape = (btCollisionShape*)*shapePtr;
btCollisionObject* body = createCollisionObject(startTransform,shape,colObjData->m_name);
btCollisionObject* body = createCollisionObject(startTransform, shape, colObjData->m_name);
#ifdef USE_INTERNAL_EDGE_UTILITY
if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE)
@@ -290,21 +270,20 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
btBvhTriangleMeshShape* trimesh = (btBvhTriangleMeshShape*)shape;
if (trimesh->getTriangleInfoMap())
{
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
}
}
#endif //USE_INTERNAL_EDGE_UTILITY
m_bodyMap.insert(colObjData,body);
} else
#endif //USE_INTERNAL_EDGE_UTILITY
m_bodyMap.insert(colObjData, body);
}
else
{
printf("error: no shape found\n");
}
}
}
for (i=0;i<bulletFile2->m_constraints.size();i++)
for (i = 0; i < bulletFile2->m_constraints.size(); i++)
{
btTypedConstraintData2* constraintData = (btTypedConstraintData2*)bulletFile2->m_constraints[i];
@@ -328,34 +307,31 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
}
if (!rbA && !rbB)
continue;
bool isDoublePrecisionData = (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION)!=0;
bool isDoublePrecisionData = (bulletFile2->getFlags() & bParse::FD_DOUBLE_PRECISION) != 0;
if (isDoublePrecisionData)
{
if (bulletFile2->getVersion()>=282)
if (bulletFile2->getVersion() >= 282)
{
btTypedConstraintDoubleData* dc = (btTypedConstraintDoubleData*)constraintData;
convertConstraintDouble(dc, rbA,rbB, bulletFile2->getVersion());
} else
convertConstraintDouble(dc, rbA, rbB, bulletFile2->getVersion());
}
else
{
//double-precision constraints were messed up until 2.82, try to recover data...
btTypedConstraintData* oldData = (btTypedConstraintData*)constraintData;
convertConstraintBackwardsCompatible281(oldData, rbA,rbB, bulletFile2->getVersion());
btTypedConstraintData* oldData = (btTypedConstraintData*)constraintData;
convertConstraintBackwardsCompatible281(oldData, rbA, rbB, bulletFile2->getVersion());
}
}
else
{
btTypedConstraintFloatData* dc = (btTypedConstraintFloatData*)constraintData;
convertConstraintFloat(dc, rbA,rbB, bulletFile2->getVersion());
convertConstraintFloat(dc, rbA, rbB, bulletFile2->getVersion());
}
}
return true;
}

View File

@@ -13,56 +13,40 @@ subject to the following restrictions:
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BULLET_WORLD_IMPORTER_H
#define BULLET_WORLD_IMPORTER_H
#include "btWorldImporter.h"
class btBulletFile;
namespace bParse
{
class btBulletFile;
class btBulletFile;
};
///The btBulletWorldImporter is a starting point to import .bullet files.
///note that not all data is converted yet. You are expected to override or modify this class.
///See Bullet/Demos/SerializeDemo for a derived class that extract btSoftBody objects too.
class btBulletWorldImporter : public btWorldImporter
{
public:
btBulletWorldImporter(btDynamicsWorld* world=0);
btBulletWorldImporter(btDynamicsWorld* world = 0);
virtual ~btBulletWorldImporter();
///if you pass a valid preSwapFilenameOut, it will save a new file with a different endianness
///if you pass a valid preSwapFilenameOut, it will save a new file with a different endianness
///this pre-swapped file can be loaded without swapping on a target platform of different endianness
bool loadFile(const char* fileName, const char* preSwapFilenameOut=0);
bool loadFile(const char* fileName, const char* preSwapFilenameOut = 0);
///the memoryBuffer might be modified (for example if endian swaps are necessary)
bool loadFileFromMemory(char *memoryBuffer, int len);
bool loadFileFromMemory(char* memoryBuffer, int len);
bool loadFileFromMemory(bParse::btBulletFile* file);
bool loadFileFromMemory(bParse::btBulletFile* file);
//call make sure bulletFile2 has been parsed, either using btBulletFile::parse or btBulletWorldImporter::loadFileFromMemory
virtual bool convertAllObjects(bParse::btBulletFile* file);
virtual bool convertAllObjects(bParse::btBulletFile* file);
};
#endif //BULLET_WORLD_IMPORTER_H
#endif //BULLET_WORLD_IMPORTER_H

View File

@@ -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;

View File

@@ -8,13 +8,12 @@ class btMultiBodyWorldImporter : public btBulletWorldImporter
struct btMultiBodyWorldImporterInternalData* m_data;
public:
btMultiBodyWorldImporter(class btMultiBodyDynamicsWorld* world);
virtual ~btMultiBodyWorldImporter();
virtual bool convertAllObjects( bParse::btBulletFile* bulletFile2);
virtual bool convertAllObjects(bParse::btBulletFile* bulletFile2);
virtual void deleteAllData();
};
#endif //BT_MULTIBODY_WORLD_IMPORTER_H
#endif //BT_MULTIBODY_WORLD_IMPORTER_H

File diff suppressed because it is too large Load Diff

View File

@@ -13,7 +13,6 @@ subject to the following restrictions:
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BT_WORLD_IMPORTER_H
#define BT_WORLD_IMPORTER_H
@@ -57,76 +56,73 @@ struct btRigidBodyFloatData;
#define btRigidBodyData btRigidBodyDoubleData
#else
#define btRigidBodyData btRigidBodyFloatData
#endif//BT_USE_DOUBLE_PRECISION
#endif //BT_USE_DOUBLE_PRECISION
enum btWorldImporterFlags
{
eRESTORE_EXISTING_OBJECTS=1,//don't create new objects
eRESTORE_EXISTING_OBJECTS = 1, //don't create new objects
};
class btWorldImporter
{
protected:
btDynamicsWorld* m_dynamicsWorld;
int m_verboseMode;
int m_importerFlags;
btAlignedObjectArray<btCollisionShape*> m_allocatedCollisionShapes;
btAlignedObjectArray<btCollisionShape*> m_allocatedCollisionShapes;
btAlignedObjectArray<btCollisionObject*> m_allocatedRigidBodies;
btAlignedObjectArray<btTypedConstraint*> m_allocatedConstraints;
btAlignedObjectArray<btOptimizedBvh*> m_allocatedBvhs;
btAlignedObjectArray<btOptimizedBvh*> m_allocatedBvhs;
btAlignedObjectArray<btTriangleInfoMap*> m_allocatedTriangleInfoMaps;
btAlignedObjectArray<btTriangleIndexVertexArray*> m_allocatedTriangleIndexArrays;
btAlignedObjectArray<btStridingMeshInterfaceData*> m_allocatedbtStridingMeshInterfaceDatas;
btAlignedObjectArray<char*> m_allocatedNames;
btAlignedObjectArray<char*> m_allocatedNames;
btAlignedObjectArray<int*> m_indexArrays;
btAlignedObjectArray<short int*> m_shortIndexArrays;
btAlignedObjectArray<unsigned char*> m_charIndexArrays;
btAlignedObjectArray<int*> m_indexArrays;
btAlignedObjectArray<short int*> m_shortIndexArrays;
btAlignedObjectArray<unsigned char*> m_charIndexArrays;
btAlignedObjectArray<btVector3FloatData*> m_floatVertexArrays;
btAlignedObjectArray<btVector3DoubleData*> m_doubleVertexArrays;
btAlignedObjectArray<btVector3FloatData*> m_floatVertexArrays;
btAlignedObjectArray<btVector3DoubleData*> m_doubleVertexArrays;
btHashMap<btHashPtr, btOptimizedBvh*> m_bvhMap;
btHashMap<btHashPtr, btTriangleInfoMap*> m_timMap;
btHashMap<btHashPtr,btOptimizedBvh*> m_bvhMap;
btHashMap<btHashPtr,btTriangleInfoMap*> m_timMap;
btHashMap<btHashString,btCollisionShape*> m_nameShapeMap;
btHashMap<btHashString,btRigidBody*> m_nameBodyMap;
btHashMap<btHashString,btTypedConstraint*> m_nameConstraintMap;
btHashMap<btHashPtr,const char*> m_objectNameMap;
btHashMap<btHashPtr,btCollisionShape*> m_shapeMap;
btHashMap<btHashPtr,btCollisionObject*> m_bodyMap;
btHashMap<btHashString, btCollisionShape*> m_nameShapeMap;
btHashMap<btHashString, btRigidBody*> m_nameBodyMap;
btHashMap<btHashString, btTypedConstraint*> m_nameConstraintMap;
btHashMap<btHashPtr, const char*> m_objectNameMap;
btHashMap<btHashPtr, btCollisionShape*> m_shapeMap;
btHashMap<btHashPtr, btCollisionObject*> m_bodyMap;
//methods
static btRigidBody& getFixedBody();
char* duplicateName(const char* name);
char* duplicateName(const char* name);
btCollisionShape* convertCollisionShape( btCollisionShapeData* shapeData );
void convertConstraintBackwardsCompatible281(btTypedConstraintData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion);
void convertConstraintFloat(btTypedConstraintFloatData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion);
void convertConstraintDouble(btTypedConstraintDoubleData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion);
void convertRigidBodyFloat(btRigidBodyFloatData* colObjData);
void convertRigidBodyDouble( btRigidBodyDoubleData* colObjData);
btCollisionShape* convertCollisionShape(btCollisionShapeData* shapeData);
void convertConstraintBackwardsCompatible281(btTypedConstraintData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion);
void convertConstraintFloat(btTypedConstraintFloatData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion);
void convertConstraintDouble(btTypedConstraintDoubleData* constraintData, btRigidBody* rbA, btRigidBody* rbB, int fileVersion);
void convertRigidBodyFloat(btRigidBodyFloatData* colObjData);
void convertRigidBodyDouble(btRigidBodyDoubleData* colObjData);
public:
btWorldImporter(btDynamicsWorld* world);
virtual ~btWorldImporter();
///delete all memory collision shapes, rigid bodies, constraints etc. allocated during the load.
///delete all memory collision shapes, rigid bodies, constraints etc. allocated during the load.
///make sure you don't use the dynamics world containing objects after you call this method
virtual void deleteAllData();
void setVerboseMode(int verboseMode)
void setVerboseMode(int verboseMode)
{
m_verboseMode = verboseMode;
}
@@ -136,7 +132,7 @@ public:
return m_verboseMode;
}
void setImporterFlags(int importerFlags)
void setImporterFlags(int importerFlags)
{
m_importerFlags = importerFlags;
}
@@ -146,87 +142,80 @@ public:
return m_importerFlags;
}
// query for data
int getNumCollisionShapes() const;
// query for data
int getNumCollisionShapes() const;
btCollisionShape* getCollisionShapeByIndex(int index);
int getNumRigidBodies() const;
btCollisionObject* getRigidBodyByIndex(int index) const;
int getNumConstraints() const;
btTypedConstraint* getConstraintByIndex(int index) const;
int getNumBvhs() const;
btOptimizedBvh* getBvhByIndex(int index) const;
btOptimizedBvh* getBvhByIndex(int index) const;
int getNumTriangleInfoMaps() const;
btTriangleInfoMap* getTriangleInfoMapByIndex(int index) const;
// queris involving named objects
btCollisionShape* getCollisionShapeByName(const char* name);
btRigidBody* getRigidBodyByName(const char* name);
btTypedConstraint* getConstraintByName(const char* name);
const char* getNameForPointer(const void* ptr) const;
const char* getNameForPointer(const void* ptr) const;
///those virtuals are called by load and can be overridden by the user
virtual void setDynamicsWorldInfo(const btVector3& gravity, const btContactSolverInfo& solverInfo);
virtual void setDynamicsWorldInfo(const btVector3& gravity, const btContactSolverInfo& solverInfo);
//bodies
virtual btRigidBody* createRigidBody(bool isDynamic, btScalar mass, const btTransform& startTransform, btCollisionShape* shape,const char* bodyName);
virtual btCollisionObject* createCollisionObject( const btTransform& startTransform, btCollisionShape* shape,const char* bodyName);
virtual btRigidBody* createRigidBody(bool isDynamic, btScalar mass, const btTransform& startTransform, btCollisionShape* shape, const char* bodyName);
virtual btCollisionObject* createCollisionObject(const btTransform& startTransform, btCollisionShape* shape, const char* bodyName);
///shapes
virtual btCollisionShape* createPlaneShape(const btVector3& planeNormal,btScalar planeConstant);
virtual btCollisionShape* createPlaneShape(const btVector3& planeNormal, btScalar planeConstant);
virtual btCollisionShape* createBoxShape(const btVector3& halfExtents);
virtual btCollisionShape* createSphereShape(btScalar radius);
virtual btCollisionShape* createCapsuleShapeX(btScalar radius, btScalar height);
virtual btCollisionShape* createCapsuleShapeY(btScalar radius, btScalar height);
virtual btCollisionShape* createCapsuleShapeZ(btScalar radius, btScalar height);
virtual btCollisionShape* createCylinderShapeX(btScalar radius,btScalar height);
virtual btCollisionShape* createCylinderShapeY(btScalar radius,btScalar height);
virtual btCollisionShape* createCylinderShapeZ(btScalar radius,btScalar height);
virtual btCollisionShape* createConeShapeX(btScalar radius,btScalar height);
virtual btCollisionShape* createConeShapeY(btScalar radius,btScalar height);
virtual btCollisionShape* createConeShapeZ(btScalar radius,btScalar height);
virtual class btTriangleIndexVertexArray* createTriangleMeshContainer();
virtual btBvhTriangleMeshShape* createBvhTriangleMeshShape(btStridingMeshInterface* trimesh, btOptimizedBvh* bvh);
virtual btCollisionShape* createCylinderShapeX(btScalar radius, btScalar height);
virtual btCollisionShape* createCylinderShapeY(btScalar radius, btScalar height);
virtual btCollisionShape* createCylinderShapeZ(btScalar radius, btScalar height);
virtual btCollisionShape* createConeShapeX(btScalar radius, btScalar height);
virtual btCollisionShape* createConeShapeY(btScalar radius, btScalar height);
virtual btCollisionShape* createConeShapeZ(btScalar radius, btScalar height);
virtual class btTriangleIndexVertexArray* createTriangleMeshContainer();
virtual btBvhTriangleMeshShape* createBvhTriangleMeshShape(btStridingMeshInterface* trimesh, btOptimizedBvh* bvh);
virtual btCollisionShape* createConvexTriangleMeshShape(btStridingMeshInterface* trimesh);
virtual btGImpactMeshShape* createGimpactShape(btStridingMeshInterface* trimesh);
virtual btStridingMeshInterfaceData* createStridingMeshInterfaceData(btStridingMeshInterfaceData* interfaceData);
virtual class btConvexHullShape* createConvexHullShape();
virtual class btCompoundShape* createCompoundShape();
virtual class btScaledBvhTriangleMeshShape* createScaledTrangleMeshShape(btBvhTriangleMeshShape* meshShape,const btVector3& localScalingbtBvhTriangleMeshShape);
virtual class btScaledBvhTriangleMeshShape* createScaledTrangleMeshShape(btBvhTriangleMeshShape* meshShape, const btVector3& localScalingbtBvhTriangleMeshShape);
virtual class btMultiSphereShape* createMultiSphereShape(const btVector3* positions,const btScalar* radi,int numSpheres);
virtual class btMultiSphereShape* createMultiSphereShape(const btVector3* positions, const btScalar* radi, int numSpheres);
virtual btTriangleIndexVertexArray* createMeshInterface(btStridingMeshInterfaceData& meshData);
///acceleration and connectivity structures
virtual btOptimizedBvh* createOptimizedBvh();
virtual btOptimizedBvh* createOptimizedBvh();
virtual btTriangleInfoMap* createTriangleInfoMap();
///constraints
virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB);
virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA,const btVector3& pivotInA);
virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA=false);
virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA,const btTransform& rbAFrame, bool useReferenceFrameA=false);
virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA,btRigidBody& rbB,const btTransform& rbAFrame, const btTransform& rbBFrame);
virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA,const btTransform& rbAFrame);
virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA);
virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameB);
virtual btGeneric6DofSpringConstraint* createGeneric6DofSpringConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA);
virtual btGeneric6DofSpring2Constraint* createGeneric6DofSpring2Constraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, int rotateOrder );
virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB ,bool useLinearReferenceFrameA);
virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameA);
virtual btGearConstraint* createGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio);
virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& pivotInA, const btVector3& pivotInB);
virtual btPoint2PointConstraint* createPoint2PointConstraint(btRigidBody& rbA, const btVector3& pivotInA);
virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA = false);
virtual btHingeConstraint* createHingeConstraint(btRigidBody& rbA, const btTransform& rbAFrame, bool useReferenceFrameA = false);
virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame);
virtual btConeTwistConstraint* createConeTwistConstraint(btRigidBody& rbA, const btTransform& rbAFrame);
virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA);
virtual btGeneric6DofConstraint* createGeneric6DofConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameB);
virtual btGeneric6DofSpringConstraint* createGeneric6DofSpringConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA);
virtual btGeneric6DofSpring2Constraint* createGeneric6DofSpring2Constraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, int rotateOrder);
virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA);
virtual btSliderConstraint* createSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameA);
virtual btGearConstraint* createGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA, const btVector3& axisInB, btScalar ratio);
};
#endif //BT_WORLD_IMPORTER_H
#endif //BT_WORLD_IMPORTER_H