Merge pull request #420 from erwincoumans/master
some work towards streaming Bullet data over shared memory for client…
This commit is contained in:
@@ -17,8 +17,8 @@
|
||||
* 3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
// Auto generated from Bullet/Extras/HeaderGenerator/bulletGenerate.py
|
||||
#ifndef __BULLET_H__
|
||||
#define __BULLET_H__
|
||||
#ifndef __BULLET2_H__
|
||||
#define __BULLET2_H__
|
||||
namespace Bullet3SerializeBullet2 {
|
||||
|
||||
// put an empty struct in the case
|
||||
@@ -1050,4 +1050,4 @@ typedef struct bInvalidHandle {
|
||||
|
||||
|
||||
}
|
||||
#endif//__BULLET_H__
|
||||
#endif//__BULLET2_H__
|
||||
@@ -1533,7 +1533,7 @@ void btCollisionWorld::serializeCollisionObjects(btSerializer* serializer)
|
||||
for (i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->getInternalType() == btCollisionObject::CO_COLLISION_OBJECT)
|
||||
if ((colObj->getInternalType() == btCollisionObject::CO_COLLISION_OBJECT) || (colObj->getInternalType() == btCollisionObject::CO_FEATHERSTONE_LINK))
|
||||
{
|
||||
colObj->serializeSingleObject(serializer);
|
||||
}
|
||||
|
||||
@@ -26,7 +26,7 @@
|
||||
#include "btMultiBodyLinkCollider.h"
|
||||
#include "btMultiBodyJointFeedback.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
|
||||
#include "LinearMath/btSerializer.h"
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
// #define INCLUDE_GYRO_TERM
|
||||
|
||||
@@ -95,6 +95,7 @@ btMultiBody::btMultiBody(int n_links,
|
||||
bool multiDof)
|
||||
:
|
||||
m_baseCollider(0),
|
||||
m_baseName(0),
|
||||
m_basePos(0,0,0),
|
||||
m_baseQuat(0, 0, 0, 1),
|
||||
m_baseMass(mass),
|
||||
@@ -400,6 +401,17 @@ btScalar * btMultiBody::getJointVelMultiDof(int i)
|
||||
return &m_realBuf[6 + m_links[i].m_dofOffset];
|
||||
}
|
||||
|
||||
const btScalar * btMultiBody::getJointPosMultiDof(int i) const
|
||||
{
|
||||
return &m_links[i].m_jointPos[0];
|
||||
}
|
||||
|
||||
const btScalar * btMultiBody::getJointVelMultiDof(int i) const
|
||||
{
|
||||
return &m_realBuf[6 + m_links[i].m_dofOffset];
|
||||
}
|
||||
|
||||
|
||||
void btMultiBody::setJointPos(int i, btScalar q)
|
||||
{
|
||||
m_links[i].m_jointPos[0] = q;
|
||||
@@ -2412,3 +2424,85 @@ void btMultiBody::forwardKinematics(btAlignedObjectArray<btQuaternion>& world_to
|
||||
|
||||
}
|
||||
|
||||
|
||||
int btMultiBody::calculateSerializeBufferSize() const
|
||||
{
|
||||
int sz = sizeof(btMultiBodyData);
|
||||
return sz;
|
||||
}
|
||||
|
||||
///fills the dataBuffer and returns the struct name (and 0 on failure)
|
||||
const char* btMultiBody::serialize(void* dataBuffer, class btSerializer* serializer) const
|
||||
{
|
||||
btMultiBodyData* mbd = (btMultiBodyData*) dataBuffer;
|
||||
getBaseWorldTransform().serialize(mbd->m_baseWorldTransform);
|
||||
mbd->m_baseMass = this->getBaseMass();
|
||||
getBaseInertia().serialize(mbd->m_baseInertia);
|
||||
{
|
||||
char* name = (char*) serializer->findNameForPointer(m_baseName);
|
||||
mbd->m_baseName = (char*)serializer->getUniquePointer(name);
|
||||
if (mbd->m_baseName)
|
||||
{
|
||||
serializer->serializeName(name);
|
||||
}
|
||||
}
|
||||
mbd->m_numLinks = this->getNumLinks();
|
||||
mbd->m_links = mbd->m_numLinks? (btMultiBodyLinkData*) serializer->getUniquePointer((void*)&m_links[0]):0;
|
||||
if (mbd->m_links)
|
||||
{
|
||||
int sz = sizeof(btMultiBodyLinkData);
|
||||
int numElem = mbd->m_numLinks;
|
||||
btChunk* chunk = serializer->allocate(sz,numElem);
|
||||
btMultiBodyLinkData* memPtr = (btMultiBodyLinkData*)chunk->m_oldPtr;
|
||||
for (int i=0;i<numElem;i++,memPtr++)
|
||||
{
|
||||
|
||||
memPtr->m_jointType = getLink(i).m_jointType;
|
||||
memPtr->m_dofCount = getLink(i).m_dofCount;
|
||||
getLink(i).m_inertiaLocal.serialize(memPtr->m_linkInertia);
|
||||
memPtr->m_linkMass = getLink(i).m_mass;
|
||||
memPtr->m_parentIndex = getLink(i).m_parent;
|
||||
getLink(i).m_eVector.serialize(memPtr->m_parentComToThisComOffset);
|
||||
getLink(i).m_dVector.serialize(memPtr->m_thisPivotToThisComOffset);
|
||||
getLink(i).m_zeroRotParentToThis.serialize(memPtr->m_zeroRotParentToThis);
|
||||
btAssert(memPtr->m_dofCount<=3);
|
||||
for (int dof = 0;dof<getLink(i).m_dofCount;dof++)
|
||||
{
|
||||
getLink(i).getAxisBottom(dof).serialize(memPtr->m_jointAxisBottom[dof]);
|
||||
getLink(i).getAxisTop(dof).serialize(memPtr->m_jointAxisTop[dof]);
|
||||
|
||||
memPtr->m_jointTorque[dof] = getLink(i).m_jointTorque[dof];
|
||||
memPtr->m_jointVel[dof] = getJointVelMultiDof(i)[dof];
|
||||
|
||||
}
|
||||
int numPosVar = getLink(i).m_posVarCount;
|
||||
for (int posvar = 0; posvar < numPosVar;posvar++)
|
||||
{
|
||||
memPtr->m_jointPos[posvar] = getLink(i).m_jointPos[posvar];
|
||||
}
|
||||
|
||||
|
||||
{
|
||||
char* name = (char*) serializer->findNameForPointer(m_links[i].m_linkName);
|
||||
memPtr->m_linkName = (char*)serializer->getUniquePointer(name);
|
||||
if (memPtr->m_linkName)
|
||||
{
|
||||
serializer->serializeName(name);
|
||||
}
|
||||
}
|
||||
{
|
||||
char* name = (char*) serializer->findNameForPointer(m_links[i].m_jointName);
|
||||
memPtr->m_jointName = (char*)serializer->getUniquePointer(name);
|
||||
if (memPtr->m_jointName)
|
||||
{
|
||||
serializer->serializeName(name);
|
||||
}
|
||||
}
|
||||
memPtr->m_linkCollider = (btCollisionObjectData*)serializer->getUniquePointer(getLink(i).m_collider);
|
||||
|
||||
}
|
||||
serializer->finalizeChunk(chunk,btMultiBodyLinkDataName,BT_ARRAY_CODE,(void*) &m_links[0]);
|
||||
}
|
||||
|
||||
return btMultiBodyDataName;
|
||||
}
|
||||
|
||||
@@ -30,6 +30,17 @@
|
||||
#include "LinearMath/btMatrix3x3.h"
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
|
||||
#ifdef BT_USE_DOUBLE_PRECISION
|
||||
#define btMultiBodyData btMultiBodyDoubleData
|
||||
#define btMultiBodyDataName "btMultiBodyDoubleData"
|
||||
#define btMultiBodyLinkData btMultiBodyLinkDoubleData
|
||||
#define btMultiBodyLinkDataName "btMultiBodyLinkDoubleData"
|
||||
#else
|
||||
#define btMultiBodyData btMultiBodyFloatData
|
||||
#define btMultiBodyDataName "btMultiBodyFloatData"
|
||||
#define btMultiBodyLinkData btMultiBodyLinkFloatData
|
||||
#define btMultiBodyLinkDataName "btMultiBodyLinkFloatData"
|
||||
#endif //BT_USE_DOUBLE_PRECISION
|
||||
|
||||
#include "btMultiBodyLink.h"
|
||||
class btMultiBodyLinkCollider;
|
||||
@@ -220,6 +231,9 @@ public:
|
||||
btScalar * getJointVelMultiDof(int i);
|
||||
btScalar * getJointPosMultiDof(int i);
|
||||
|
||||
const btScalar * getJointVelMultiDof(int i) const ;
|
||||
const btScalar * getJointPosMultiDof(int i) const ;
|
||||
|
||||
void setJointPos(int i, btScalar q);
|
||||
void setJointVel(int i, btScalar qdot);
|
||||
void setJointPosMultiDof(int i, btScalar *q);
|
||||
@@ -586,6 +600,20 @@ void addJointTorque(int i, btScalar Q);
|
||||
}
|
||||
void forwardKinematics(btAlignedObjectArray<btQuaternion>& scratch_q,btAlignedObjectArray<btVector3>& scratch_m);
|
||||
|
||||
virtual int calculateSerializeBufferSize() const;
|
||||
|
||||
///fills the dataBuffer and returns the struct name (and 0 on failure)
|
||||
virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
|
||||
|
||||
const char* getBaseName() const
|
||||
{
|
||||
return m_baseName;
|
||||
}
|
||||
///memory of setBaseName needs to be manager by user
|
||||
void setBaseName(const char* name)
|
||||
{
|
||||
m_baseName = name;
|
||||
}
|
||||
|
||||
private:
|
||||
btMultiBody(const btMultiBody &); // not implemented
|
||||
@@ -608,11 +636,11 @@ private:
|
||||
|
||||
void mulMatrix(btScalar *pA, btScalar *pB, int rowsA, int colsA, int rowsB, int colsB, btScalar *pC) const;
|
||||
|
||||
|
||||
|
||||
private:
|
||||
|
||||
btMultiBodyLinkCollider* m_baseCollider;//can be NULL
|
||||
const char* m_baseName;//memory needs to be manager by user!
|
||||
|
||||
btVector3 m_basePos; // position of COM of base (world frame)
|
||||
btQuaternion m_baseQuat; // rotates world points into base frame
|
||||
@@ -679,4 +707,96 @@ private:
|
||||
bool m_internalNeedsJointFeedback;
|
||||
};
|
||||
|
||||
struct btMultiBodyLinkDoubleData
|
||||
{
|
||||
btQuaternionDoubleData m_zeroRotParentToThis;
|
||||
btVector3DoubleData m_parentComToThisComOffset;
|
||||
btVector3DoubleData m_thisPivotToThisComOffset;
|
||||
btVector3DoubleData m_jointAxisTop[6];
|
||||
btVector3DoubleData m_jointAxisBottom[6];
|
||||
|
||||
|
||||
char *m_linkName;
|
||||
char *m_jointName;
|
||||
btCollisionObjectDoubleData *m_linkCollider;
|
||||
|
||||
btVector3DoubleData m_linkInertia; // inertia of the base (in local frame; diagonal)
|
||||
double m_linkMass;
|
||||
int m_parentIndex;
|
||||
int m_jointType;
|
||||
|
||||
|
||||
|
||||
|
||||
int m_dofCount;
|
||||
int m_posVarCount;
|
||||
double m_jointPos[7];
|
||||
double m_jointVel[6];
|
||||
double m_jointTorque[6];
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
struct btMultiBodyLinkFloatData
|
||||
{
|
||||
btQuaternionFloatData m_zeroRotParentToThis;
|
||||
btVector3FloatData m_parentComToThisComOffset;
|
||||
btVector3FloatData m_thisPivotToThisComOffset;
|
||||
btVector3FloatData m_jointAxisTop[6];
|
||||
btVector3FloatData m_jointAxisBottom[6];
|
||||
|
||||
|
||||
char *m_linkName;
|
||||
char *m_jointName;
|
||||
btCollisionObjectFloatData *m_linkCollider;
|
||||
|
||||
btVector3FloatData m_linkInertia; // inertia of the base (in local frame; diagonal)
|
||||
int m_dofCount;
|
||||
float m_linkMass;
|
||||
int m_parentIndex;
|
||||
int m_jointType;
|
||||
|
||||
|
||||
|
||||
float m_jointPos[7];
|
||||
float m_jointVel[6];
|
||||
float m_jointTorque[6];
|
||||
int m_posVarCount;
|
||||
|
||||
|
||||
};
|
||||
|
||||
///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
|
||||
struct btMultiBodyDoubleData
|
||||
{
|
||||
char *m_baseName;
|
||||
btMultiBodyLinkDoubleData *m_links;
|
||||
btCollisionObjectDoubleData *m_baseCollider;
|
||||
|
||||
btTransformDoubleData m_baseWorldTransform;
|
||||
btVector3DoubleData m_baseInertia; // inertia of the base (in local frame; diagonal)
|
||||
|
||||
int m_numLinks;
|
||||
double m_baseMass;
|
||||
|
||||
char m_padding[4];
|
||||
|
||||
};
|
||||
|
||||
///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
|
||||
struct btMultiBodyFloatData
|
||||
{
|
||||
char *m_baseName;
|
||||
btMultiBodyLinkFloatData *m_links;
|
||||
btCollisionObjectFloatData *m_baseCollider;
|
||||
btTransformFloatData m_baseWorldTransform;
|
||||
btVector3FloatData m_baseInertia; // inertia of the base (in local frame; diagonal)
|
||||
|
||||
float m_baseMass;
|
||||
int m_numLinks;
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
@@ -21,7 +21,7 @@ subject to the following restrictions:
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
#include "btMultiBodyConstraint.h"
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
|
||||
#include "LinearMath/btSerializer.h"
|
||||
|
||||
|
||||
void btMultiBodyDynamicsWorld::addMultiBody(btMultiBody* body, short group, short mask)
|
||||
@@ -1011,3 +1011,37 @@ void btMultiBodyDynamicsWorld::clearForces()
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void btMultiBodyDynamicsWorld::serialize(btSerializer* serializer)
|
||||
{
|
||||
|
||||
serializer->startSerialization();
|
||||
|
||||
serializeDynamicsWorldInfo( serializer);
|
||||
|
||||
serializeMultiBodies(serializer);
|
||||
|
||||
serializeRigidBodies(serializer);
|
||||
|
||||
serializeCollisionObjects(serializer);
|
||||
|
||||
serializer->finishSerialization();
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::serializeMultiBodies(btSerializer* serializer)
|
||||
{
|
||||
int i;
|
||||
//serialize all collision objects
|
||||
for (i=0;i<m_multiBodies.size();i++)
|
||||
{
|
||||
btMultiBody* mb = m_multiBodies[i];
|
||||
{
|
||||
int len = mb->calculateSerializeBufferSize();
|
||||
btChunk* chunk = serializer->allocate(len,1);
|
||||
const char* structType = mb->serialize(chunk->m_oldPtr, serializer);
|
||||
serializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
@@ -40,6 +40,8 @@ protected:
|
||||
virtual void updateActivationState(btScalar timeStep);
|
||||
virtual void solveConstraints(btContactSolverInfo& solverInfo);
|
||||
|
||||
virtual void serializeMultiBodies(btSerializer* serializer);
|
||||
|
||||
public:
|
||||
|
||||
btMultiBodyDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btMultiBodyConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration);
|
||||
@@ -91,5 +93,7 @@ public:
|
||||
virtual void clearMultiBodyForces();
|
||||
virtual void applyGravity();
|
||||
|
||||
virtual void serialize(btSerializer* serializer);
|
||||
|
||||
};
|
||||
#endif //BT_MULTIBODY_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -127,6 +127,9 @@ btVector3 m_appliedConstraintForce; // In WORLD frame
|
||||
|
||||
btTransform m_cachedWorldTransform;//this cache is updated when calling btMultiBody::forwardKinematics
|
||||
|
||||
const char* m_linkName;//m_linkName memory needs to be managed by the developer/user!
|
||||
const char* m_jointName;//m_jointName memory needs to be managed by the developer/user!
|
||||
|
||||
// ctor: set some sensible defaults
|
||||
btMultibodyLink()
|
||||
: m_mass(1),
|
||||
@@ -138,8 +141,9 @@ btVector3 m_appliedConstraintForce; // In WORLD frame
|
||||
m_dofCount(0),
|
||||
m_posVarCount(0),
|
||||
m_jointType(btMultibodyLink::eInvalid),
|
||||
m_jointFeedback(0)
|
||||
|
||||
m_jointFeedback(0),
|
||||
m_linkName(0),
|
||||
m_jointName(0)
|
||||
{
|
||||
|
||||
m_inertiaLocal.setValue(1, 1, 1);
|
||||
|
||||
@@ -22,6 +22,13 @@ subject to the following restrictions:
|
||||
#include "btQuadWord.h"
|
||||
|
||||
|
||||
#ifdef BT_USE_DOUBLE_PRECISION
|
||||
#define btQuaternionData btQuaternionDoubleData
|
||||
#define btQuaternionDataName "btQuaternionDoubleData"
|
||||
#else
|
||||
#define btQuaternionData btQuaternionFloatData
|
||||
#define btQuaternionDataName "btQuaternionFloatData"
|
||||
#endif //BT_USE_DOUBLE_PRECISION
|
||||
|
||||
|
||||
|
||||
@@ -560,7 +567,18 @@ public:
|
||||
|
||||
SIMD_FORCE_INLINE const btScalar& getW() const { return m_floats[3]; }
|
||||
|
||||
|
||||
SIMD_FORCE_INLINE void serialize(struct btQuaternionData& dataOut) const;
|
||||
|
||||
SIMD_FORCE_INLINE void deSerialize(const struct btQuaternionData& dataIn);
|
||||
|
||||
SIMD_FORCE_INLINE void serializeFloat(struct btQuaternionFloatData& dataOut) const;
|
||||
|
||||
SIMD_FORCE_INLINE void deSerializeFloat(const struct btQuaternionFloatData& dataIn);
|
||||
|
||||
SIMD_FORCE_INLINE void serializeDouble(struct btQuaternionDoubleData& dataOut) const;
|
||||
|
||||
SIMD_FORCE_INLINE void deSerializeDouble(const struct btQuaternionDoubleData& dataIn);
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -903,6 +921,62 @@ shortestArcQuatNormalize2(btVector3& v0,btVector3& v1)
|
||||
return shortestArcQuat(v0,v1);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
struct btQuaternionFloatData
|
||||
{
|
||||
float m_floats[4];
|
||||
};
|
||||
|
||||
struct btQuaternionDoubleData
|
||||
{
|
||||
double m_floats[4];
|
||||
|
||||
};
|
||||
|
||||
SIMD_FORCE_INLINE void btQuaternion::serializeFloat(struct btQuaternionFloatData& dataOut) const
|
||||
{
|
||||
///could also do a memcpy, check if it is worth it
|
||||
for (int i=0;i<4;i++)
|
||||
dataOut.m_floats[i] = float(m_floats[i]);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void btQuaternion::deSerializeFloat(const struct btQuaternionFloatData& dataIn)
|
||||
{
|
||||
for (int i=0;i<4;i++)
|
||||
m_floats[i] = btScalar(dataIn.m_floats[i]);
|
||||
}
|
||||
|
||||
|
||||
SIMD_FORCE_INLINE void btQuaternion::serializeDouble(struct btQuaternionDoubleData& dataOut) const
|
||||
{
|
||||
///could also do a memcpy, check if it is worth it
|
||||
for (int i=0;i<4;i++)
|
||||
dataOut.m_floats[i] = double(m_floats[i]);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void btQuaternion::deSerializeDouble(const struct btQuaternionDoubleData& dataIn)
|
||||
{
|
||||
for (int i=0;i<4;i++)
|
||||
m_floats[i] = btScalar(dataIn.m_floats[i]);
|
||||
}
|
||||
|
||||
|
||||
SIMD_FORCE_INLINE void btQuaternion::serialize(struct btQuaternionData& dataOut) const
|
||||
{
|
||||
///could also do a memcpy, check if it is worth it
|
||||
for (int i=0;i<4;i++)
|
||||
dataOut.m_floats[i] = m_floats[i];
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void btQuaternion::deSerialize(const struct btQuaternionData& dataIn)
|
||||
{
|
||||
for (int i=0;i<4;i++)
|
||||
m_floats[i] = dataIn.m_floats[i];
|
||||
}
|
||||
|
||||
|
||||
#endif //BT_SIMD__QUATERNION_H_
|
||||
|
||||
|
||||
|
||||
@@ -28,7 +28,7 @@ subject to the following restrictions:
|
||||
#include <float.h>
|
||||
|
||||
/* SVN $Revision$ on $Date$ from http://bullet.googlecode.com*/
|
||||
#define BT_BULLET_VERSION 283
|
||||
#define BT_BULLET_VERSION 284
|
||||
|
||||
inline int btGetVersion()
|
||||
{
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -113,6 +113,8 @@ public:
|
||||
# define BT_MAKE_ID(a,b,c,d) ( (int)(d)<<24 | (int)(c)<<16 | (b)<<8 | (a) )
|
||||
#endif
|
||||
|
||||
|
||||
#define BT_MULTIBODY_CODE BT_MAKE_ID('M','B','D','Y')
|
||||
#define BT_SOFTBODY_CODE BT_MAKE_ID('S','B','D','Y')
|
||||
#define BT_COLLISIONOBJECT_CODE BT_MAKE_ID('C','O','B','J')
|
||||
#define BT_RIGIDBODY_CODE BT_MAKE_ID('R','B','D','Y')
|
||||
@@ -206,7 +208,7 @@ protected:
|
||||
|
||||
|
||||
|
||||
void writeDNA()
|
||||
virtual void writeDNA()
|
||||
{
|
||||
btChunk* dnaChunk = allocate(m_dnaLength,1);
|
||||
memcpy(dnaChunk->m_oldPtr,m_dna,m_dnaLength);
|
||||
@@ -465,7 +467,7 @@ public:
|
||||
|
||||
buffer[9] = '2';
|
||||
buffer[10] = '8';
|
||||
buffer[11] = '3';
|
||||
buffer[11] = '4';
|
||||
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user