Get the open source Bullet library more in sync with Playstation SPU version

This commit is contained in:
ejcoumans 2007-04-10 01:02:58 +00:00
parent 9546633ade
commit 853bafb7ae
25 changed files with 272 additions and 130 deletions

View File

@ -299,9 +299,9 @@ public:
for(i=0;i<3;i++)
{
for(j=0;j<3;j++ )
{
m_AR[i][j] = 1e-6f + fabsf(m_R1to0[i][j]);
for(j=0;j<3;j++ )
{
m_AR[i][j] = 1e-6f + fabsf(m_R1to0[i][j]);
}
}
}

View File

@ -81,7 +81,7 @@ btConcaveConcaveCollisionAlgorithm::~btConcaveConcaveCollisionAlgorithm()
void btConcaveConcaveCollisionAlgorithm::clearCache()
{
btPersistentManifold* mainfold;
for (size_t i=0;i<this->m_mainfoldsPtr.size() ; i++)
for (int i=0;i<this->m_mainfoldsPtr.size() ; i++)
{
mainfold = m_mainfoldsPtr[i];
m_dispatcher->releaseManifold(mainfold);

View File

@ -62,7 +62,7 @@ CONCAVE_SHAPES_END_HERE,
///btBroadphaseProxy
struct btBroadphaseProxy
ATTRIBUTE_ALIGNED16(struct) btBroadphaseProxy
{
///optional filtering to cull potential collisions
@ -115,7 +115,8 @@ struct btBroadphaseProxy
return (proxyType == STATIC_PLANE_PROXYTYPE);
}
};
}
;
class btCollisionAlgorithm;
@ -130,14 +131,16 @@ struct btBroadphasePair
:
m_pProxy0(0),
m_pProxy1(0),
m_algorithm(0)
m_algorithm(0),
m_userInfo(0)
{
}
btBroadphasePair(const btBroadphasePair& other)
: m_pProxy0(other.m_pProxy0),
m_pProxy1(other.m_pProxy1),
m_algorithm(other.m_algorithm)
m_algorithm(other.m_algorithm),
m_userInfo(other.m_userInfo)
{
}
btBroadphasePair(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
@ -156,6 +159,7 @@ struct btBroadphasePair
}
m_algorithm = 0;
m_userInfo = 0;
}
@ -163,6 +167,8 @@ struct btBroadphasePair
btBroadphaseProxy* m_pProxy1;
mutable btCollisionAlgorithm* m_algorithm;
mutable void* m_userInfo;
};
/*

View File

@ -37,48 +37,61 @@ virtual ~btOverlapCallback()
///Typically managed by the Broadphase, Axis3Sweep or btSimpleBroadphase
class btOverlappingPairCache : public btBroadphaseInterface
{
protected:
//avoid brute-force finding all the time
btAlignedObjectArray<btBroadphasePair> m_overlappingPairArray;
//during the dispatch, check that user doesn't destroy/create proxy
bool m_blockedForChanges;
protected:
//avoid brute-force finding all the time
btAlignedObjectArray<btBroadphasePair> m_overlappingPairArray;
//during the dispatch, check that user doesn't destroy/create proxy
bool m_blockedForChanges;
public:
btOverlappingPairCache();
virtual ~btOverlappingPairCache();
virtual void processAllOverlappingPairs(btOverlapCallback*);
void removeOverlappingPair(btBroadphasePair& pair);
void cleanOverlappingPair(btBroadphasePair& pair);
btOverlappingPairCache();
virtual ~btOverlappingPairCache();
void addOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1);
virtual void processAllOverlappingPairs(btOverlapCallback*);
void removeOverlappingPair(btBroadphasePair& pair);
void cleanOverlappingPair(btBroadphasePair& pair);
void addOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1);
btBroadphasePair* findPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1);
btBroadphasePair* findPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1);
void cleanProxyFromPairs(btBroadphaseProxy* proxy);
void cleanProxyFromPairs(btBroadphaseProxy* proxy);
void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy);
void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy);
inline bool needsBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const
{
bool collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
collides = collides && (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
inline bool needsBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const
{
bool collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
collides = collides && (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
return collides;
}
return collides;
}
virtual void refreshOverlappingPairs() =0;
btBroadphasePair* getOverlappingPairArrayPtr()
{
return &m_overlappingPairArray[0];
}
const btBroadphasePair* getOverlappingPairArrayPtr() const
{
return &m_overlappingPairArray[0];
}
int getNumOverlappingPairs() const
{
return m_overlappingPairArray.size();
}
virtual void refreshOverlappingPairs() =0;
};
#endif //OVERLAPPING_PAIR_CACHE_H

View File

@ -34,7 +34,7 @@ class btCollisionShape;
/// btCollisionObject can be used to manage collision detection objects.
/// btCollisionObject maintains all information that is needed for a collision detection: Shape, Transform and AABB proxy.
/// They can be added to the btCollisionWorld.
class btCollisionObject
ATTRIBUTE_ALIGNED16(class) btCollisionObject
{
protected:
@ -320,6 +320,7 @@ public:
m_userObjectPointer = userPointer;
}
};
}
;
#endif //COLLISION_OBJECT_H

View File

@ -18,6 +18,7 @@ subject to the following restrictions:
#include "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h"
#include "BulletCollision/CollisionShapes/btOptimizedBvh.h"
///Bvh Concave triangle mesh is a static-triangle mesh shape with Bounding Volume Hierarchy optimization.
///Uses an interface to access the triangles to allow for sharing graphics/physics triangles.
btBvhTriangleMeshShape::btBvhTriangleMeshShape(btStridingMeshInterface* meshInterface, bool useQuantizedAabbCompression)
@ -94,12 +95,14 @@ void btBvhTriangleMeshShape::processAllTriangles(btTriangleCallback* callback,co
nodeSubPart);
int* gfxbase = (int*)(indexbase+nodeTriangleIndex*indexstride);
const btVector3& meshScaling = m_meshInterface->getScaling();
for (int j=2;j>=0;j--)
{
int graphicsindex = gfxbase[j];
#ifdef DEBUG_TRIANGLE_MESH
printf("%d ,",graphicsindex);
#endif //DEBUG_TRIANGLE_MESH

View File

@ -21,13 +21,15 @@ subject to the following restrictions:
///Bvh Concave triangle mesh is a static-triangle mesh shape with Bounding Volume Hierarchy optimization.
///Uses an interface to access the triangles to allow for sharing graphics/physics triangles.
class btBvhTriangleMeshShape : public btTriangleMeshShape
ATTRIBUTE_ALIGNED16(class) btBvhTriangleMeshShape : public btTriangleMeshShape
{
btOptimizedBvh* m_bvh;
bool m_useQuantizedAabbCompression;
public:
btBvhTriangleMeshShape() :btTriangleMeshShape(0) {};
btBvhTriangleMeshShape(btStridingMeshInterface* meshInterface, bool useQuantizedAabbCompression);
virtual ~btBvhTriangleMeshShape();
@ -52,8 +54,15 @@ public:
virtual void setLocalScaling(const btVector3& scaling);
};
btOptimizedBvh* getOptimizedBvh()
{
return m_bvh;
}
bool usesQuantizedAabbCompression() const
{
return m_useQuantizedAabbCompression;
}
}
;
#endif //BVH_TRIANGLE_MESH_SHAPE_H

View File

@ -42,12 +42,13 @@ public:
///getAngularMotionDisc returns the maximus radius needed for Conservative Advancement to handle time-of-impact with rotations.
virtual btScalar getAngularMotionDisc() const;
virtual int getShapeType() const=0;
///calculateTemporalAabb calculates the enclosing aabb for the moving object over interval [0..timeStep)
///result is conservative
void calculateTemporalAabb(const btTransform& curTrans,const btVector3& linvel,const btVector3& angvel,btScalar timeStep, btVector3& temporalAabbMin,btVector3& temporalAabbMax);
#ifndef __SPU__
inline bool isPolyhedral() const
{
return btBroadphaseProxy::isPolyhedral(getShapeType());
@ -72,13 +73,16 @@ public:
return btBroadphaseProxy::isInfinite(getShapeType());
}
virtual int getShapeType() const=0;
virtual void setLocalScaling(const btVector3& scaling) =0;
virtual const btVector3& getLocalScaling() const =0;
virtual void calculateLocalInertia(btScalar mass,btVector3& inertia) = 0;
//debugging support
virtual char* getName()const =0 ;
#endif //__SPU__
const char* getExtraDebugInfo() const { return m_tempDebug;}
void setExtraDebugInfo(const char* extraDebugInfo) { m_tempDebug = extraDebugInfo;}
const char * m_tempDebug;

View File

@ -15,6 +15,7 @@ subject to the following restrictions:
#include "btConvexShape.h"
btConvexShape::btConvexShape()
: m_localScaling(btScalar(1.),btScalar(1.),btScalar(1.)),
m_collisionMargin(CONVEX_DISTANCE_MARGIN)
@ -48,8 +49,11 @@ void btConvexShape::getAabbSlow(const btTransform& trans,btVector3&minAabb,btVec
}
};
btVector3 btConvexShape::localGetSupportingVertex(const btVector3& vec)const
{
{
#ifndef __SPU__
btVector3 supVertex = localGetSupportingVertexWithoutMargin(vec);
if ( getMargin()!=btScalar(0.) )
@ -64,6 +68,10 @@ btVector3 btConvexShape::localGetSupportingVertex(const btVector3& vec)const
}
return supVertex;
#else
return btVector3(0,0,0);
#endif //__SPU__
}

View File

@ -30,9 +30,9 @@ struct btConvexCastResult;
/// btConvexShape is an abstract shape interface.
/// The explicit part provides plane-equations, the implicit part provides GetClosestPoint interface.
/// used in combination with GJK or btConvexCast
class btConvexShape : public btCollisionShape
ATTRIBUTE_ALIGNED16(class) btConvexShape : public btCollisionShape
{
protected:
//local scaling. collisionMargin is not scaled !
@ -46,11 +46,19 @@ protected:
public:
btConvexShape();
virtual ~btConvexShape()
{
}
virtual btVector3 localGetSupportingVertex(const btVector3& vec)const;
#ifndef __SPU__
virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec) const= 0;
//notice that the vectors should be unit length
virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const= 0;
#endif //#ifndef __SPU__
const btVector3& getImplicitShapeDimensions() const
{
@ -74,6 +82,10 @@ public:
return m_localScaling;
}
const btVector3& getLocalScalingNV() const
{
return m_localScaling;
}
virtual void setMargin(btScalar margin)
{
@ -84,6 +96,11 @@ public:
return m_collisionMargin;
}
btScalar getMarginNV() const
{
return m_collisionMargin;
}
virtual int getNumPreferredPenetrationDirections() const
{
return 0;
@ -96,7 +113,8 @@ public:
};
}
;

View File

@ -16,7 +16,8 @@ subject to the following restrictions:
#include "LinearMath/btPoint3.h"
btCylinderShape::btCylinderShape (const btVector3& halfExtents)
:btBoxShape(halfExtents)
:btBoxShape(halfExtents),
m_upAxis(1)
{
recalcLocalAabb();
}
@ -25,6 +26,7 @@ btCylinderShape::btCylinderShape (const btVector3& halfExtents)
btCylinderShapeX::btCylinderShapeX (const btVector3& halfExtents)
:btCylinderShape(halfExtents)
{
m_upAxis = 0;
recalcLocalAabb();
}
@ -32,6 +34,7 @@ btCylinderShapeX::btCylinderShapeX (const btVector3& halfExtents)
btCylinderShapeZ::btCylinderShapeZ (const btVector3& halfExtents)
:btCylinderShape(halfExtents)
{
m_upAxis = 2;
recalcLocalAabb();
}

View File

@ -25,6 +25,10 @@ class btCylinderShape : public btBoxShape
{
protected:
int m_upAxis;
public:
btCylinderShape (const btVector3& halfExtents);
@ -63,9 +67,9 @@ public:
return CYLINDER_SHAPE_PROXYTYPE;
}
virtual int getUpAxis() const
int getUpAxis() const
{
return 1;
return m_upAxis;
}
virtual btScalar getRadius() const
@ -90,10 +94,7 @@ public:
virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec)const;
virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const;
virtual int getUpAxis() const
{
return 0;
}
//debugging
virtual char* getName()const
{

View File

@ -18,8 +18,7 @@ subject to the following restrictions:
#include "LinearMath/btAabbUtil2.h"
#include "LinearMath/btIDebugDraw.h"
//Note: currently we have 16 bytes per quantized node
static const int MAX_SUBTREE_SIZE_IN_BYTES = 16384;
btOptimizedBvh::btOptimizedBvh() : m_useQuantization(false),
m_traversalMode(TRAVERSAL_STACKLESS_CACHE_FRIENDLY)
@ -178,12 +177,14 @@ void btOptimizedBvh::refit(btStridingMeshInterface* meshInterface)
PHY_ScalarType indicestype;
meshInterface->getLockedReadOnlyVertexIndexBase(&vertexbase,numverts, type,stride,&indexbase,indexstride,numfaces,indicestype,nodeSubPart);
btVector3 triangleVerts[3];
btVector3 aabbMin,aabbMax;
const btVector3& meshScaling = meshInterface->getScaling();
int numNodes = m_curNodeIndex;
int i;
for (i=numNodes-1;i>=0;i--)
{
btVector3 triangleVerts[3];
btQuantizedBvhNode& curNode = m_quantizedContiguousNodes[i];
if (curNode.isLeafNode())
@ -194,7 +195,7 @@ void btOptimizedBvh::refit(btStridingMeshInterface* meshInterface)
int* gfxbase = (int*)(indexbase+nodeTriangleIndex*indexstride);
const btVector3& meshScaling = meshInterface->getScaling();
for (int j=2;j>=0;j--)
{
@ -208,7 +209,7 @@ void btOptimizedBvh::refit(btStridingMeshInterface* meshInterface)
}
btVector3 aabbMin,aabbMax;
aabbMin.setValue(btScalar(1e30),btScalar(1e30),btScalar(1e30));
aabbMax.setValue(btScalar(-1e30),btScalar(-1e30),btScalar(-1e30));
aabbMin.setMin(triangleVerts[0]);
@ -220,9 +221,7 @@ void btOptimizedBvh::refit(btStridingMeshInterface* meshInterface)
quantizeWithClamp(&curNode.m_quantizedAabbMin[0],aabbMin);
quantizeWithClamp(&curNode.m_quantizedAabbMax[0],aabbMax);
int k;
k=0;
} else
{
//combine aabb from both children
@ -231,8 +230,7 @@ void btOptimizedBvh::refit(btStridingMeshInterface* meshInterface)
btQuantizedBvhNode* rightChildNode = leftChildNode->isLeafNode() ? &m_quantizedContiguousNodes[i+2] :
&m_quantizedContiguousNodes[i+1+leftChildNode->getEscapeIndex()];
int k;
k=0;
{
for (int i=0;i<3;i++)

View File

@ -26,10 +26,13 @@ subject to the following restrictions:
class btStridingMeshInterface;
//Note: currently we have 16 bytes per quantized node
#define MAX_SUBTREE_SIZE_IN_BYTES 2048
///btQuantizedBvhNode is a compressed aabb node, 16 bytes.
///Node can be used for leafnode or internal node. Leafnodes can point to 32-bit triangle index (non-negative range).
ATTRIBUTE_ALIGNED16 (struct btQuantizedBvhNode)
ATTRIBUTE_ALIGNED16 (struct) btQuantizedBvhNode
{
//12 bytes
@ -53,11 +56,12 @@ ATTRIBUTE_ALIGNED16 (struct btQuantizedBvhNode)
btAssert(isLeafNode());
return m_escapeIndexOrTriangleIndex;
}
};
}
;
/// btOptimizedBvhNode contains both internal and leaf node information.
/// Total node size is 44 bytes / node. You can use the compressed version of 16 bytes.
ATTRIBUTE_ALIGNED16 (struct btOptimizedBvhNode)
ATTRIBUTE_ALIGNED16 (struct) btOptimizedBvhNode
{
//32 bytes
btVector3 m_aabbMinOrg;
@ -74,6 +78,30 @@ ATTRIBUTE_ALIGNED16 (struct btOptimizedBvhNode)
};
///btBvhSubtreeInfo provides info to gather a subtree of limited size
ATTRIBUTE_ALIGNED16(class) btBvhSubtreeInfo
{
public:
//12 bytes
unsigned short int m_quantizedAabbMin[3];
unsigned short int m_quantizedAabbMax[3];
//4 bytes, points to the root of the subtree
int m_rootNodeIndex;
//4 bytes
int m_subtreeSize;
void setAabbFromQuantizeNode(const btQuantizedBvhNode& quantizedNode)
{
m_quantizedAabbMin[0] = quantizedNode.m_quantizedAabbMin[0];
m_quantizedAabbMin[1] = quantizedNode.m_quantizedAabbMin[1];
m_quantizedAabbMin[2] = quantizedNode.m_quantizedAabbMin[2];
m_quantizedAabbMax[0] = quantizedNode.m_quantizedAabbMax[0];
m_quantizedAabbMax[1] = quantizedNode.m_quantizedAabbMax[1];
m_quantizedAabbMax[2] = quantizedNode.m_quantizedAabbMax[2];
}
}
;
class btNodeOverlapCallback
{
@ -88,13 +116,14 @@ public:
///for code readability:
typedef btAlignedObjectArray<btOptimizedBvhNode> NodeArray;
typedef btAlignedObjectArray<btQuantizedBvhNode> QuantizedNodeArray;
typedef btAlignedObjectArray<btBvhSubtreeInfo> BvhSubtreeInfoArray;
///OptimizedBvh store an AABB tree that can be quickly traversed on CPU (and SPU,GPU in future)
ATTRIBUTE_ALIGNED16(class btOptimizedBvh)
ATTRIBUTE_ALIGNED16(class) btOptimizedBvh
{
NodeArray m_leafNodes;
NodeArray m_contiguousNodes;
@ -121,30 +150,10 @@ ATTRIBUTE_ALIGNED16(class btOptimizedBvh)
btTraversalMode m_traversalMode;
///btBvhSubtreeInfo provides info to gather a subtree of limited size
class btBvhSubtreeInfo
{
public:
//12 bytes
unsigned short int m_quantizedAabbMin[3];
unsigned short int m_quantizedAabbMax[3];
//4 bytes, points to the root of the subtree
int m_rootNodeIndex;
//4 bytes
int m_subtreeSize;
void setAabbFromQuantizeNode(const btQuantizedBvhNode& quantizedNode)
{
m_quantizedAabbMin[0] = quantizedNode.m_quantizedAabbMin[0];
m_quantizedAabbMin[1] = quantizedNode.m_quantizedAabbMin[1];
m_quantizedAabbMin[2] = quantizedNode.m_quantizedAabbMin[2];
m_quantizedAabbMax[0] = quantizedNode.m_quantizedAabbMax[0];
m_quantizedAabbMax[1] = quantizedNode.m_quantizedAabbMax[1];
m_quantizedAabbMax[2] = quantizedNode.m_quantizedAabbMax[2];
}
};
btAlignedObjectArray<btBvhSubtreeInfo> m_SubtreeHeaders;
BvhSubtreeInfoArray m_SubtreeHeaders;
///two versions, one for quantized and normal nodes. This allows code-reuse while maintaining readability (no template/macro!)
@ -295,7 +304,19 @@ public:
}
void refit(btStridingMeshInterface* triangles);
};
QuantizedNodeArray& getQuantizedNodeArray()
{
return m_quantizedContiguousNodes;
}
BvhSubtreeInfoArray& getSubtreeInfoArray()
{
return m_SubtreeHeaders;
}
}
;
#endif //OPTIMIZED_BVH_H

View File

@ -20,10 +20,10 @@ btTriangleIndexVertexArray::btTriangleIndexVertexArray(int numTriangles,int* tri
btIndexedMesh mesh;
mesh.m_numTriangles = numTriangles;
mesh.m_triangleIndexBase = triangleIndexBase;
mesh.m_triangleIndexBase = (const unsigned char *)triangleIndexBase;
mesh.m_triangleIndexStride = triangleIndexStride;
mesh.m_numVertices = numVertices;
mesh.m_vertexBase = vertexBase;
mesh.m_vertexBase = (const unsigned char *)vertexBase;
mesh.m_vertexStride = vertexStride;
addIndexedMesh(mesh);

View File

@ -22,29 +22,31 @@ subject to the following restrictions:
///IndexedMesh indexes into existing vertex and index arrays, in a similar way OpenGL glDrawElements
///instead of the number of indices, we pass the number of triangles
///todo: explain with pictures
struct btIndexedMesh
{
int m_numTriangles;
int* m_triangleIndexBase;
int m_triangleIndexStride;
int m_numVertices;
btScalar* m_vertexBase;
int m_vertexStride;
};
ATTRIBUTE_ALIGNED16( struct) btIndexedMesh
{
int m_numTriangles;
const unsigned char * m_triangleIndexBase;
int m_triangleIndexStride;
int m_numVertices;
const unsigned char * m_vertexBase;
int m_vertexStride;
}
;
typedef btAlignedObjectArray<btIndexedMesh> IndexedMeshArray;
///TriangleIndexVertexArray allows to use multiple meshes, by indexing into existing triangle/index arrays.
///Additional meshes can be added using addIndexedMesh
///No duplcate is made of the vertex/index data, it only indexes into external vertex/index arrays.
///So keep those arrays around during the lifetime of this btTriangleIndexVertexArray.
class btTriangleIndexVertexArray : public btStridingMeshInterface
ATTRIBUTE_ALIGNED16( class) btTriangleIndexVertexArray : public btStridingMeshInterface
{
btAlignedObjectArray<btIndexedMesh> m_indexedMeshes;
IndexedMeshArray m_indexedMeshes;
public:
btTriangleIndexVertexArray()
{
}
@ -73,10 +75,21 @@ public:
virtual int getNumSubParts() const {
return (int)m_indexedMeshes.size();
}
IndexedMeshArray& getIndexedMeshArray()
{
return m_indexedMeshes;
}
const IndexedMeshArray& getIndexedMeshArray() const
{
return m_indexedMeshes;
}
virtual void preallocateVertices(int numverts){}
virtual void preallocateIndices(int numindices){}
};
}
;
#endif //BT_TRIANGLE_INDEX_VERTEX_ARRAY_H

View File

@ -58,6 +58,16 @@ public:
virtual void setLocalScaling(const btVector3& scaling);
virtual const btVector3& getLocalScaling() const;
btStridingMeshInterface* getMeshInterface()
{
return m_meshInterface;
}
const btStridingMeshInterface* getMeshInterface() const
{
return m_meshInterface;
}
//debugging
virtual char* getName()const {return "TRIANGLEMESH";}

View File

@ -36,7 +36,7 @@ extern ContactDestroyedCallback gContactDestroyedCallback;
///btPersistentManifold maintains contact points, and reduces them to 4.
///It does contact filtering/contact reduction.
class btPersistentManifold
ATTRIBUTE_ALIGNED16( class) btPersistentManifold
{
btManifoldPoint m_pointCache[MANIFOLD_CACHE_SIZE];
@ -145,7 +145,8 @@ public:
};
}
;

View File

@ -23,7 +23,7 @@ class btRigidBody;
ATTRIBUTE_ALIGNED16 (struct btSolverBody)
ATTRIBUTE_ALIGNED16 (struct) btSolverBody
{
btVector3 m_centerOfMassPosition;
btVector3 m_linearVelocity;

View File

@ -25,7 +25,7 @@ class btRigidBody;
//#define NO_FRICTION_TANGENTIALS 1
///1D constraint along a normal axis between bodyA and bodyB. It can be combined to solve contact and friction constraints.
ATTRIBUTE_ALIGNED16 (struct btSolverConstraint)
ATTRIBUTE_ALIGNED16 (struct) btSolverConstraint
{
btVector3 m_relpos1CrossNormal;
btVector3 m_relpos2CrossNormal;

View File

@ -31,6 +31,26 @@ void btAlignedFree (void* ptr)
#else
#ifdef __CELLOS_LV2__
#include <stdlib.h>
int numAllocs = 0;
int numFree = 0;
void* btAlignedAlloc (int size, int alignment)
{
numAllocs++;
return memalign(alignment, size);
}
void btAlignedFree (void* ptr)
{
numFree++;
free(ptr);
}
#else
///todo
///will add some multi-platform version that works without _aligned_malloc/_aligned_free
@ -43,6 +63,7 @@ void btAlignedFree (void* ptr)
{
delete [] (char*) ptr;
}
#endif //
#endif

View File

@ -40,7 +40,7 @@ class btAlignedObjectArray
SIMD_FORCE_INLINE void copy(int start,int end, T* dest)
{
int i;
for (i=0;i<m_size;++i)
for (i=start;i<end;++i)
dest[i] = m_data[i];
}
@ -53,7 +53,7 @@ class btAlignedObjectArray
SIMD_FORCE_INLINE void destroy(int first,int last)
{
int i;
for (i=0; i<m_size;i++)
for (i=first; i<last;i++)
{
m_data[i].~T();
}

View File

@ -21,7 +21,8 @@ subject to the following restrictions:
ATTRIBUTE_ALIGNED16 (class btQuadWord)
///btQuadWord is base-class for vectors, points
class btQuadWord
{
protected:
btScalar m_x;

View File

@ -43,6 +43,17 @@ subject to the following restrictions:
#define btFullAssert(x)
#else
#if defined (__CELLOS_LV2__)
#define SIMD_FORCE_INLINE inline
#define ATTRIBUTE_ALIGNED16(a) a __attribute__ ((aligned (16)))
#ifndef assert
#include <assert.h>
#endif
#define btAssert assert
//btFullAssert is optional, slows down a lot
#define btFullAssert(x)
#else
//non-windows systems
#define SIMD_FORCE_INLINE inline
@ -53,6 +64,7 @@ subject to the following restrictions:
#define btAssert assert
//btFullAssert is optional, slows down a lot
#define btFullAssert(x)
#endif //__CELLOS_LV2__
#endif
/// older compilers (gcc 3.x) and Sun needs double version of sqrt etc.

View File

@ -19,11 +19,10 @@ subject to the following restrictions:
#include "btQuadWord.h"
///btVector3 is 16byte aligned, and has an extra unused component m_w
///this extra component can be used by derived classes (Quaternion?) or by user
class btVector3 : public btQuadWord {
///btVector3 can be used to represent 3D points and vectors.
///It has an un-used w component to suit 16-byte alignment when btVector3 is stored in containers. This extra component can be used by derived classes (Quaternion?) or by user
///Ideally, this class should be replaced by a platform optimized SIMD version that keeps the data in registers
class btVector3 : public btQuadWord {
public:
SIMD_FORCE_INLINE btVector3() {}