Apple contribution for OSX SSE and iOS NEON optimizations unit tests, thanks to Jordan Hubbard, Ian Ollmann and Hristo Hristov.
For OSX: cd build ./premake_osx xcode4 for iOS: cd build ./ios_build.sh ./ios_run.sh Also integrated the branches/StackAllocation to make it easier to multi-thread collision detection in the near future. It avoids changing the btCollisionObject while performing collision detection. As this is a large patch, some stuff might be temporarily broken, I'll keep an eye out on issues.
This commit is contained in:
@@ -48,7 +48,7 @@ static char* ComputeBoundsHLSLString =
|
||||
#include "HLSL/ComputeBounds.hlsl"
|
||||
static char* SolveCollisionsAndUpdateVelocitiesHLSLString =
|
||||
#include "HLSL/SolveCollisionsAndUpdateVelocities.hlsl"
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
|
||||
|
||||
btSoftBodyLinkDataDX11::btSoftBodyLinkDataDX11( ID3D11Device *d3dDevice, ID3D11DeviceContext *d3dDeviceContext ) :
|
||||
m_dx11Links( d3dDevice, d3dDeviceContext, &m_links, false ),
|
||||
@@ -2162,14 +2162,14 @@ void btDX11SoftBodySolver::processCollision( btSoftBody*, btSoftBody* )
|
||||
}
|
||||
|
||||
// Add the collision object to the set to deal with for a particular soft body
|
||||
void btDX11SoftBodySolver::processCollision( btSoftBody *softBody, btCollisionObject* collisionObject )
|
||||
void btDX11SoftBodySolver::processCollision( btSoftBody *softBody, const btCollisionObjectWrapper* collisionObject )
|
||||
{
|
||||
int softBodyIndex = findSoftBodyIndex( softBody );
|
||||
|
||||
if( softBodyIndex >= 0 )
|
||||
{
|
||||
btCollisionShape *collisionShape = collisionObject->getCollisionShape();
|
||||
float friction = collisionObject->getFriction();
|
||||
const btCollisionShape *collisionShape = collisionObject->getCollisionShape();
|
||||
float friction = collisionObject->getCollisionObject()->getFriction();
|
||||
int shapeType = collisionShape->getShapeType();
|
||||
if( shapeType == CAPSULE_SHAPE_PROXYTYPE )
|
||||
{
|
||||
@@ -2179,12 +2179,12 @@ void btDX11SoftBodySolver::processCollision( btSoftBody *softBody, btCollisionOb
|
||||
newCollisionShapeDescription.collisionShapeType = shapeType;
|
||||
// TODO: May need to transpose this matrix either here or in HLSL
|
||||
newCollisionShapeDescription.shapeTransform = toTransform3(collisionObject->getWorldTransform());
|
||||
btCapsuleShape *capsule = static_cast<btCapsuleShape*>( collisionShape );
|
||||
const btCapsuleShape *capsule = static_cast<const btCapsuleShape*>( collisionShape );
|
||||
newCollisionShapeDescription.radius = capsule->getRadius();
|
||||
newCollisionShapeDescription.halfHeight = capsule->getHalfHeight();
|
||||
newCollisionShapeDescription.margin = capsule->getMargin();
|
||||
newCollisionShapeDescription.friction = friction;
|
||||
btRigidBody* body = static_cast< btRigidBody* >( collisionObject );
|
||||
const btRigidBody* body = static_cast< const btRigidBody* >( collisionObject->getCollisionObject() );
|
||||
newCollisionShapeDescription.linearVelocity = toVector3(body->getLinearVelocity());
|
||||
newCollisionShapeDescription.angularVelocity = toVector3(body->getAngularVelocity());
|
||||
m_collisionObjectDetails.push_back( newCollisionShapeDescription );
|
||||
|
||||
@@ -614,7 +614,7 @@ public:
|
||||
virtual void predictMotion( float solverdt );
|
||||
|
||||
|
||||
virtual void processCollision( btSoftBody *, btCollisionObject* );
|
||||
virtual void processCollision( btSoftBody *, const btCollisionObjectWrapper* );
|
||||
|
||||
virtual void processCollision( btSoftBody*, btSoftBody* );
|
||||
|
||||
|
||||
@@ -25,7 +25,7 @@ subject to the following restrictions:
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
#include <limits.h>
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
|
||||
|
||||
#define BT_SUPPRESS_OPENCL_ASSERTS
|
||||
|
||||
@@ -770,7 +770,7 @@ void btOpenCLSoftBodySolver::optimize( btAlignedObjectArray< btSoftBody * > &sof
|
||||
desc.setInverseMass(vertexInverseMass);
|
||||
getVertexData().setVertexAt( desc, firstVertex + vertex );
|
||||
|
||||
m_anchorIndex.push_back(-1.0);
|
||||
m_anchorIndex.push_back(-1);
|
||||
}
|
||||
|
||||
// Copy triangles similarly
|
||||
@@ -1707,14 +1707,14 @@ void btOpenCLSoftBodySolver::processCollision( btSoftBody*, btSoftBody* )
|
||||
}
|
||||
|
||||
// Add the collision object to the set to deal with for a particular soft body
|
||||
void btOpenCLSoftBodySolver::processCollision( btSoftBody *softBody, btCollisionObject* collisionObject )
|
||||
void btOpenCLSoftBodySolver::processCollision( btSoftBody *softBody, const btCollisionObjectWrapper* collisionObject )
|
||||
{
|
||||
int softBodyIndex = findSoftBodyIndex( softBody );
|
||||
|
||||
if( softBodyIndex >= 0 )
|
||||
{
|
||||
btCollisionShape *collisionShape = collisionObject->getCollisionShape();
|
||||
float friction = collisionObject->getFriction();
|
||||
const btCollisionShape *collisionShape = collisionObject->getCollisionShape();
|
||||
float friction = collisionObject->getCollisionObject()->getFriction();
|
||||
int shapeType = collisionShape->getShapeType();
|
||||
if( shapeType == CAPSULE_SHAPE_PROXYTYPE )
|
||||
{
|
||||
@@ -1724,13 +1724,13 @@ void btOpenCLSoftBodySolver::processCollision( btSoftBody *softBody, btCollision
|
||||
newCollisionShapeDescription.collisionShapeType = shapeType;
|
||||
// TODO: May need to transpose this matrix either here or in HLSL
|
||||
newCollisionShapeDescription.shapeTransform = toTransform3(collisionObject->getWorldTransform());
|
||||
btCapsuleShape *capsule = static_cast<btCapsuleShape*>( collisionShape );
|
||||
const btCapsuleShape *capsule = static_cast<const btCapsuleShape*>( collisionShape );
|
||||
newCollisionShapeDescription.radius = capsule->getRadius();
|
||||
newCollisionShapeDescription.halfHeight = capsule->getHalfHeight();
|
||||
newCollisionShapeDescription.margin = capsule->getMargin();
|
||||
newCollisionShapeDescription.upAxis = capsule->getUpAxis();
|
||||
newCollisionShapeDescription.friction = friction;
|
||||
btRigidBody* body = static_cast< btRigidBody* >( collisionObject );
|
||||
const btRigidBody* body = static_cast< const btRigidBody* >( collisionObject->getCollisionObject() );
|
||||
newCollisionShapeDescription.linearVelocity = toVector3(body->getLinearVelocity());
|
||||
newCollisionShapeDescription.angularVelocity = toVector3(body->getAngularVelocity());
|
||||
m_collisionObjectDetails.push_back( newCollisionShapeDescription );
|
||||
|
||||
@@ -481,7 +481,7 @@ public:
|
||||
|
||||
virtual void predictMotion( float solverdt );
|
||||
|
||||
virtual void processCollision( btSoftBody *, btCollisionObject* );
|
||||
virtual void processCollision( btSoftBody *, const btCollisionObjectWrapper* );
|
||||
|
||||
virtual void processCollision( btSoftBody*, btSoftBody* );
|
||||
|
||||
|
||||
@@ -251,7 +251,7 @@ void btOpenCLSoftBodySolverSIMDAware::optimize( btAlignedObjectArray< btSoftBody
|
||||
desc.setInverseMass(vertexInverseMass);
|
||||
getVertexData().setVertexAt( desc, firstVertex + vertex );
|
||||
|
||||
m_anchorIndex.push_back(-1.0);
|
||||
m_anchorIndex.push_back(-1);
|
||||
}
|
||||
for( int vertex = numVertices; vertex < maxVertices; ++vertex )
|
||||
{
|
||||
|
||||
@@ -22,7 +22,7 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
|
||||
void SpuContactManifoldCollisionAlgorithm::processCollision (btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
|
||||
void SpuContactManifoldCollisionAlgorithm::processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
|
||||
{
|
||||
btAssert(0);
|
||||
}
|
||||
|
||||
@@ -45,7 +45,7 @@ ATTRIBUTE_ALIGNED16(class) SpuContactManifoldCollisionAlgorithm : public btColli
|
||||
|
||||
public:
|
||||
|
||||
virtual void processCollision (btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
|
||||
virtual void processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
|
||||
|
||||
virtual btScalar calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ subject to the following restrictions:
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
#include "BulletMultiThreaded/SpuNarrowPhaseCollisionTask/SpuCollisionShapes.h"
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
|
||||
|
||||
|
||||
|
||||
@@ -166,7 +166,10 @@ public:
|
||||
collisionPair.m_internalTmpValue = 2;
|
||||
} else
|
||||
{
|
||||
collisionPair.m_algorithm = m_dispatcher->findAlgorithm(colObj0,colObj1);
|
||||
btCollisionObjectWrapper ob0(0,colObj0->getCollisionShape(),colObj0,colObj0->getWorldTransform());
|
||||
btCollisionObjectWrapper ob1(0,colObj1->getCollisionShape(),colObj1,colObj1->getWorldTransform());
|
||||
|
||||
collisionPair.m_algorithm = m_dispatcher->findAlgorithm(&ob0,&ob1);
|
||||
collisionPair.m_internalTmpValue = 3;
|
||||
}
|
||||
}
|
||||
@@ -241,12 +244,16 @@ void SpuGatheringCollisionDispatcher::dispatchAllCollisionPairs(btOverlappingPai
|
||||
|
||||
if (dispatcher->needsCollision(colObj0,colObj1))
|
||||
{
|
||||
btManifoldResult contactPointResult(colObj0,colObj1);
|
||||
//discrete collision detection query
|
||||
btCollisionObjectWrapper ob0(0,colObj0->getCollisionShape(),colObj0,colObj0->getWorldTransform());
|
||||
btCollisionObjectWrapper ob1(0,colObj1->getCollisionShape(),colObj1,colObj1->getWorldTransform());
|
||||
|
||||
btManifoldResult contactPointResult(&ob0,&ob1);
|
||||
|
||||
if (dispatchInfo.m_dispatchFunc == btDispatcherInfo::DISPATCH_DISCRETE)
|
||||
{
|
||||
//discrete collision detection query
|
||||
collisionPair.m_algorithm->processCollision(colObj0,colObj1,dispatchInfo,&contactPointResult);
|
||||
|
||||
collisionPair.m_algorithm->processCollision(&ob0,&ob1,dispatchInfo,&contactPointResult);
|
||||
} else
|
||||
{
|
||||
//continuous collision detection query, time of impact (toi)
|
||||
|
||||
@@ -44,7 +44,7 @@ void computeAabb (btVector3& aabbMin, btVector3& aabbMax, btConvexInternalShape*
|
||||
const btTransform& t = xform;
|
||||
btMatrix3x3 abs_b = t.getBasis().absolute();
|
||||
btVector3 center = t.getOrigin();
|
||||
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
|
||||
btVector3 extent = halfExtents.dot3( abs_b[0], abs_b[1], abs_b[2] );
|
||||
|
||||
aabbMin = center - extent;
|
||||
aabbMax = center + extent;
|
||||
@@ -67,7 +67,7 @@ void computeAabb (btVector3& aabbMin, btVector3& aabbMax, btConvexInternalShape*
|
||||
const btTransform& t = xform;
|
||||
btMatrix3x3 abs_b = t.getBasis().absolute();
|
||||
btVector3 center = t.getOrigin();
|
||||
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));
|
||||
btVector3 extent = halfExtents.dot3( abs_b[0], abs_b[1], abs_b[2] );
|
||||
|
||||
aabbMin = center - extent;
|
||||
aabbMax = center + extent;
|
||||
|
||||
@@ -1364,8 +1364,8 @@ void processCollisionTask(void* userPtr, void* lsMemPtr)
|
||||
)
|
||||
{
|
||||
handleCollisionPair(collisionPairInput, lsMem, spuContacts,
|
||||
(ppu_address_t)lsMem.getColObj0()->getRootCollisionShape(), &lsMem.gCollisionShapes[0].collisionShape,
|
||||
(ppu_address_t)lsMem.getColObj1()->getRootCollisionShape(), &lsMem.gCollisionShapes[1].collisionShape);
|
||||
(ppu_address_t)lsMem.getColObj0()->getCollisionShape(), &lsMem.gCollisionShapes[0].collisionShape,
|
||||
(ppu_address_t)lsMem.getColObj1()->getCollisionShape(), &lsMem.gCollisionShapes[1].collisionShape);
|
||||
} else
|
||||
{
|
||||
//spu_printf("boxbox dist = %f\n",distance);
|
||||
|
||||
@@ -1,79 +1,79 @@
|
||||
/*
|
||||
Copyright (C) 2009 Sony Computer Entertainment Inc.
|
||||
All rights reserved.
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef BT_RB_DYN_BODY_H__
|
||||
#define BT_RB_DYN_BODY_H__
|
||||
|
||||
#include "vectormath/vmInclude.h"
|
||||
using namespace Vectormath::Aos;
|
||||
|
||||
#include "TrbStateVec.h"
|
||||
|
||||
class CollObject;
|
||||
|
||||
class TrbDynBody
|
||||
{
|
||||
public:
|
||||
TrbDynBody()
|
||||
{
|
||||
fMass = 0.0f;
|
||||
fCollObject = NULL;
|
||||
fElasticity = 0.2f;
|
||||
fFriction = 0.8f;
|
||||
}
|
||||
|
||||
// Get methods
|
||||
float getMass() const {return fMass;};
|
||||
float getElasticity() const {return fElasticity;}
|
||||
float getFriction() const {return fFriction;}
|
||||
CollObject* getCollObject() const {return fCollObject;}
|
||||
const Matrix3 &getBodyInertia() const {return fIBody;}
|
||||
const Matrix3 &getBodyInertiaInv() const {return fIBodyInv;}
|
||||
float getMassInv() const {return fMassInv;}
|
||||
|
||||
// Set methods
|
||||
void setMass(float mass) {fMass=mass;fMassInv=mass>0.0f?1.0f/mass:0.0f;}
|
||||
void setBodyInertia(const Matrix3 bodyInertia) {fIBody = bodyInertia;fIBodyInv = inverse(bodyInertia);}
|
||||
void setElasticity(float elasticity) {fElasticity = elasticity;}
|
||||
void setFriction(float friction) {fFriction = friction;}
|
||||
void setCollObject(CollObject *collObj) {fCollObject = collObj;}
|
||||
|
||||
void setBodyInertiaInv(const Matrix3 bodyInertiaInv)
|
||||
{
|
||||
fIBody = inverse(bodyInertiaInv);
|
||||
fIBodyInv = bodyInertiaInv;
|
||||
}
|
||||
void setMassInv(float invMass) {
|
||||
fMass= invMass>0.0f ? 1.0f/invMass :0.0f;
|
||||
fMassInv=invMass;
|
||||
}
|
||||
|
||||
|
||||
private:
|
||||
// Rigid Body constants
|
||||
float fMass; // Rigid Body mass
|
||||
float fMassInv; // Inverse of mass
|
||||
Matrix3 fIBody; // Inertia matrix in body's coords
|
||||
Matrix3 fIBodyInv; // Inertia matrix inverse in body's coords
|
||||
float fElasticity; // Coefficient of restitution
|
||||
float fFriction; // Coefficient of friction
|
||||
|
||||
public:
|
||||
CollObject* fCollObject; // Collision object corresponding the RB
|
||||
} __attribute__ ((aligned(16)));
|
||||
|
||||
#endif //BT_RB_DYN_BODY_H__
|
||||
|
||||
/*
|
||||
Copyright (C) 2009 Sony Computer Entertainment Inc.
|
||||
All rights reserved.
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef BT_RB_DYN_BODY_H__
|
||||
#define BT_RB_DYN_BODY_H__
|
||||
|
||||
#include "vectormath/vmInclude.h"
|
||||
using namespace Vectormath::Aos;
|
||||
|
||||
#include "TrbStateVec.h"
|
||||
|
||||
class CollObject;
|
||||
|
||||
class TrbDynBody
|
||||
{
|
||||
public:
|
||||
TrbDynBody()
|
||||
{
|
||||
fMass = 0.0f;
|
||||
fCollObject = NULL;
|
||||
fElasticity = 0.2f;
|
||||
fFriction = 0.8f;
|
||||
}
|
||||
|
||||
// Get methods
|
||||
float getMass() const {return fMass;};
|
||||
float getElasticity() const {return fElasticity;}
|
||||
float getFriction() const {return fFriction;}
|
||||
CollObject* getCollObject() const {return fCollObject;}
|
||||
const Matrix3 &getBodyInertia() const {return fIBody;}
|
||||
const Matrix3 &getBodyInertiaInv() const {return fIBodyInv;}
|
||||
float getMassInv() const {return fMassInv;}
|
||||
|
||||
// Set methods
|
||||
void setMass(float mass) {fMass=mass;fMassInv=mass>0.0f?1.0f/mass:0.0f;}
|
||||
void setBodyInertia(const Matrix3 bodyInertia) {fIBody = bodyInertia;fIBodyInv = inverse(bodyInertia);}
|
||||
void setElasticity(float elasticity) {fElasticity = elasticity;}
|
||||
void setFriction(float friction) {fFriction = friction;}
|
||||
void setCollObject(CollObject *collObj) {fCollObject = collObj;}
|
||||
|
||||
void setBodyInertiaInv(const Matrix3 bodyInertiaInv)
|
||||
{
|
||||
fIBody = inverse(bodyInertiaInv);
|
||||
fIBodyInv = bodyInertiaInv;
|
||||
}
|
||||
void setMassInv(float invMass) {
|
||||
fMass= invMass>0.0f ? 1.0f/invMass :0.0f;
|
||||
fMassInv=invMass;
|
||||
}
|
||||
|
||||
|
||||
private:
|
||||
// Rigid Body constants
|
||||
float fMass; // Rigid Body mass
|
||||
float fMassInv; // Inverse of mass
|
||||
Matrix3 fIBody; // Inertia matrix in body's coords
|
||||
Matrix3 fIBodyInv; // Inertia matrix inverse in body's coords
|
||||
float fElasticity; // Coefficient of restitution
|
||||
float fFriction; // Coefficient of friction
|
||||
|
||||
public:
|
||||
CollObject* fCollObject; // Collision object corresponding the RB
|
||||
} __attribute__ ((aligned(16)));
|
||||
|
||||
#endif //BT_RB_DYN_BODY_H__
|
||||
|
||||
|
||||
@@ -1,339 +1,339 @@
|
||||
/*
|
||||
Copyright (C) 2009 Sony Computer Entertainment Inc.
|
||||
All rights reserved.
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef BT_TRBSTATEVEC_H__
|
||||
#define BT_TRBSTATEVEC_H__
|
||||
|
||||
#include <stdlib.h>
|
||||
#ifdef PFX_USE_FREE_VECTORMATH
|
||||
#include "vecmath/vmInclude.h"
|
||||
#else
|
||||
#include "vectormath/vmInclude.h"
|
||||
#endif //PFX_USE_FREE_VECTORMATH
|
||||
|
||||
|
||||
#include "PlatformDefinitions.h"
|
||||
|
||||
|
||||
static inline vmVector3 read_Vector3(const float* p)
|
||||
{
|
||||
vmVector3 v;
|
||||
loadXYZ(v, p);
|
||||
return v;
|
||||
}
|
||||
|
||||
static inline vmQuat read_Quat(const float* p)
|
||||
{
|
||||
vmQuat vq;
|
||||
loadXYZW(vq, p);
|
||||
return vq;
|
||||
}
|
||||
|
||||
static inline void store_Vector3(const vmVector3 &src, float* p)
|
||||
{
|
||||
vmVector3 v = src;
|
||||
storeXYZ(v, p);
|
||||
}
|
||||
|
||||
static inline void store_Quat(const vmQuat &src, float* p)
|
||||
{
|
||||
vmQuat vq = src;
|
||||
storeXYZW(vq, p);
|
||||
}
|
||||
|
||||
// Motion Type
|
||||
enum {
|
||||
PfxMotionTypeFixed = 0,
|
||||
PfxMotionTypeActive,
|
||||
PfxMotionTypeKeyframe,
|
||||
PfxMotionTypeOneWay,
|
||||
PfxMotionTypeTrigger,
|
||||
PfxMotionTypeCount
|
||||
};
|
||||
|
||||
#define PFX_MOTION_MASK_DYNAMIC 0x0a // Active,OneWay
|
||||
#define PFX_MOTION_MASK_STATIC 0x95 // Fixed,Keyframe,Trigger,Sleeping
|
||||
#define PFX_MOTION_MASK_SLEEP 0x0e // Can sleep
|
||||
#define PFX_MOTION_MASK_TYPE 0x7f
|
||||
|
||||
//
|
||||
// Rigid Body state
|
||||
//
|
||||
|
||||
#ifdef __CELLOS_LV2__
|
||||
ATTRIBUTE_ALIGNED128(class) TrbState
|
||||
#else
|
||||
ATTRIBUTE_ALIGNED16(class) TrbState
|
||||
#endif
|
||||
|
||||
{
|
||||
public:
|
||||
TrbState()
|
||||
{
|
||||
setMotionType(PfxMotionTypeActive);
|
||||
contactFilterSelf=contactFilterTarget=0xffffffff;
|
||||
deleted = 0;
|
||||
mSleeping = 0;
|
||||
useSleep = 1;
|
||||
trbBodyIdx=0;
|
||||
mSleepCount=0;
|
||||
useCcd = 0;
|
||||
useContactCallback = 0;
|
||||
useSleepCallback = 0;
|
||||
linearDamping = 1.0f;
|
||||
angularDamping = 0.99f;
|
||||
}
|
||||
|
||||
TrbState(const uint8_t m, const vmVector3& x, const vmQuat& q, const vmVector3& v, const vmVector3& omega );
|
||||
|
||||
uint16_t mSleepCount;
|
||||
uint8_t mMotionType;
|
||||
uint8_t deleted : 1;
|
||||
uint8_t mSleeping : 1;
|
||||
uint8_t useSleep : 1;
|
||||
uint8_t useCcd : 1;
|
||||
uint8_t useContactCallback : 1;
|
||||
uint8_t useSleepCallback : 1;
|
||||
|
||||
uint16_t trbBodyIdx;
|
||||
uint32_t contactFilterSelf;
|
||||
uint32_t contactFilterTarget;
|
||||
|
||||
float center[3]; // AABB center(World)
|
||||
float half[3]; // AABB half(World)
|
||||
|
||||
float linearDamping;
|
||||
float angularDamping;
|
||||
|
||||
float deltaLinearVelocity[3];
|
||||
float deltaAngularVelocity[3];
|
||||
|
||||
float fX[3]; // position
|
||||
float fQ[4]; // orientation
|
||||
float fV[3]; // velocity
|
||||
float fOmega[3]; // angular velocity
|
||||
|
||||
inline void setZero(); // Zeroes out the elements
|
||||
inline void setIdentity(); // Sets the rotation to identity and zeroes out the other elements
|
||||
|
||||
bool isDeleted() const {return deleted==1;}
|
||||
|
||||
uint16_t getRigidBodyId() const {return trbBodyIdx;}
|
||||
void setRigidBodyId(uint16_t i) {trbBodyIdx = i;}
|
||||
|
||||
|
||||
uint32_t getContactFilterSelf() const {return contactFilterSelf;}
|
||||
void setContactFilterSelf(uint32_t filter) {contactFilterSelf = filter;}
|
||||
|
||||
uint32_t getContactFilterTarget() const {return contactFilterTarget;}
|
||||
void setContactFilterTarget(uint32_t filter) {contactFilterTarget = filter;}
|
||||
|
||||
float getLinearDamping() const {return linearDamping;}
|
||||
float getAngularDamping() const {return angularDamping;}
|
||||
|
||||
void setLinearDamping(float damping) {linearDamping=damping;}
|
||||
void setAngularDamping(float damping) {angularDamping=damping;}
|
||||
|
||||
|
||||
uint8_t getMotionType() const {return mMotionType;}
|
||||
void setMotionType(uint8_t t) {mMotionType = t;mSleeping=0;mSleepCount=0;}
|
||||
|
||||
uint8_t getMotionMask() const {return (1<<mMotionType)|(mSleeping<<7);}
|
||||
|
||||
bool isAsleep() const {return mSleeping==1;}
|
||||
bool isAwake() const {return mSleeping==0;}
|
||||
|
||||
void wakeup() {mSleeping=0;mSleepCount=0;}
|
||||
void sleep() {if(useSleep) {mSleeping=1;mSleepCount=0;}}
|
||||
|
||||
uint8_t getUseSleep() const {return useSleep;}
|
||||
void setUseSleep(uint8_t b) {useSleep=b;}
|
||||
|
||||
uint8_t getUseCcd() const {return useCcd;}
|
||||
void setUseCcd(uint8_t b) {useCcd=b;}
|
||||
|
||||
uint8_t getUseContactCallback() const {return useContactCallback;}
|
||||
void setUseContactCallback(uint8_t b) {useContactCallback=b;}
|
||||
|
||||
uint8_t getUseSleepCallback() const {return useSleepCallback;}
|
||||
void setUseSleepCallback(uint8_t b) {useSleepCallback=b;}
|
||||
|
||||
void incrementSleepCount() {mSleepCount++;}
|
||||
void resetSleepCount() {mSleepCount=0;}
|
||||
uint16_t getSleepCount() const {return mSleepCount;}
|
||||
|
||||
vmVector3 getPosition() const {return read_Vector3(fX);}
|
||||
vmQuat getOrientation() const {return read_Quat(fQ);}
|
||||
vmVector3 getLinearVelocity() const {return read_Vector3(fV);}
|
||||
vmVector3 getAngularVelocity() const {return read_Vector3(fOmega);}
|
||||
vmVector3 getDeltaLinearVelocity() const {return read_Vector3(deltaLinearVelocity);}
|
||||
vmVector3 getDeltaAngularVelocity() const {return read_Vector3(deltaAngularVelocity);}
|
||||
|
||||
void setPosition(const vmVector3 &pos) {store_Vector3(pos, fX);}
|
||||
void setLinearVelocity(const vmVector3 &vel) {store_Vector3(vel, fV);}
|
||||
void setAngularVelocity(const vmVector3 &vel) {store_Vector3(vel, fOmega);}
|
||||
void setDeltaLinearVelocity(const vmVector3 &vel) {store_Vector3(vel, deltaLinearVelocity);}
|
||||
void setDeltaAngularVelocity(const vmVector3 &vel) {store_Vector3(vel, deltaAngularVelocity);}
|
||||
void setOrientation(const vmQuat &rot) {store_Quat(rot, fQ);}
|
||||
|
||||
inline void setAuxils(const vmVector3 ¢erLocal,const vmVector3 &halfLocal);
|
||||
inline void setAuxilsCcd(const vmVector3 ¢erLocal,const vmVector3 &halfLocal,float timeStep);
|
||||
inline void reset();
|
||||
};
|
||||
|
||||
inline
|
||||
TrbState::TrbState(const uint8_t m, const vmVector3& x, const vmQuat& q, const vmVector3& v, const vmVector3& omega)
|
||||
{
|
||||
setMotionType(m);
|
||||
fX[0] = x[0];
|
||||
fX[1] = x[1];
|
||||
fX[2] = x[2];
|
||||
fQ[0] = q[0];
|
||||
fQ[1] = q[1];
|
||||
fQ[2] = q[2];
|
||||
fQ[3] = q[3];
|
||||
fV[0] = v[0];
|
||||
fV[1] = v[1];
|
||||
fV[2] = v[2];
|
||||
fOmega[0] = omega[0];
|
||||
fOmega[1] = omega[1];
|
||||
fOmega[2] = omega[2];
|
||||
contactFilterSelf=contactFilterTarget=0xffff;
|
||||
trbBodyIdx=0;
|
||||
mSleeping = 0;
|
||||
deleted = 0;
|
||||
useSleep = 1;
|
||||
useCcd = 0;
|
||||
useContactCallback = 0;
|
||||
useSleepCallback = 0;
|
||||
mSleepCount=0;
|
||||
linearDamping = 1.0f;
|
||||
angularDamping = 0.99f;
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setIdentity()
|
||||
{
|
||||
fX[0] = 0.0f;
|
||||
fX[1] = 0.0f;
|
||||
fX[2] = 0.0f;
|
||||
fQ[0] = 0.0f;
|
||||
fQ[1] = 0.0f;
|
||||
fQ[2] = 0.0f;
|
||||
fQ[3] = 1.0f;
|
||||
fV[0] = 0.0f;
|
||||
fV[1] = 0.0f;
|
||||
fV[2] = 0.0f;
|
||||
fOmega[0] = 0.0f;
|
||||
fOmega[1] = 0.0f;
|
||||
fOmega[2] = 0.0f;
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setZero()
|
||||
{
|
||||
fX[0] = 0.0f;
|
||||
fX[1] = 0.0f;
|
||||
fX[2] = 0.0f;
|
||||
fQ[0] = 0.0f;
|
||||
fQ[1] = 0.0f;
|
||||
fQ[2] = 0.0f;
|
||||
fQ[3] = 0.0f;
|
||||
fV[0] = 0.0f;
|
||||
fV[1] = 0.0f;
|
||||
fV[2] = 0.0f;
|
||||
fOmega[0] = 0.0f;
|
||||
fOmega[1] = 0.0f;
|
||||
fOmega[2] = 0.0f;
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setAuxils(const vmVector3 ¢erLocal,const vmVector3 &halfLocal)
|
||||
{
|
||||
vmVector3 centerW = getPosition() + rotate(getOrientation(),centerLocal);
|
||||
vmVector3 halfW = absPerElem(vmMatrix3(getOrientation())) * halfLocal;
|
||||
center[0] = centerW[0];
|
||||
center[1] = centerW[1];
|
||||
center[2] = centerW[2];
|
||||
half[0] = halfW[0];
|
||||
half[1] = halfW[1];
|
||||
half[2] = halfW[2];
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setAuxilsCcd(const vmVector3 ¢erLocal,const vmVector3 &halfLocal,float timeStep)
|
||||
{
|
||||
vmVector3 centerW = getPosition() + rotate(getOrientation(),centerLocal);
|
||||
vmVector3 halfW = absPerElem(vmMatrix3(getOrientation())) * halfLocal;
|
||||
|
||||
vmVector3 diffvec = getLinearVelocity()*timeStep;
|
||||
|
||||
vmVector3 newCenter = centerW + diffvec;
|
||||
vmVector3 aabbMin = minPerElem(newCenter - halfW,centerW - halfW);
|
||||
vmVector3 aabbMax = maxPerElem(newCenter + halfW,centerW + halfW);
|
||||
|
||||
centerW = 0.5f * (aabbMin + aabbMax);
|
||||
halfW =0.5f * (aabbMax - aabbMin);
|
||||
|
||||
center[0] = centerW[0];
|
||||
center[1] = centerW[1];
|
||||
center[2] = centerW[2];
|
||||
|
||||
half[0] = halfW[0];
|
||||
half[1] = halfW[1];
|
||||
half[2] = halfW[2];
|
||||
}
|
||||
|
||||
inline
|
||||
void TrbState::reset()
|
||||
{
|
||||
#if 0
|
||||
mSleepCount = 0;
|
||||
mMotionType = PfxMotionTypeActive;
|
||||
mDeleted = 0;
|
||||
mSleeping = 0;
|
||||
mUseSleep = 1;
|
||||
mUseCcd = 0;
|
||||
mUseContactCallback = 0;
|
||||
mUseSleepCallback = 0;
|
||||
mRigidBodyId = 0;
|
||||
mContactFilterSelf = 0xffffffff;
|
||||
mContactFilterTarget = 0xffffffff;
|
||||
mLinearDamping = 1.0f;
|
||||
mAngularDamping = 0.99f;
|
||||
mPosition = vmVector3(0.0f);
|
||||
mOrientation = vmQuat::identity();
|
||||
mLinearVelocity = vmVector3(0.0f);
|
||||
mAngularVelocity = vmVector3(0.0f);
|
||||
#endif
|
||||
|
||||
setMotionType(PfxMotionTypeActive);
|
||||
contactFilterSelf=contactFilterTarget=0xffffffff;
|
||||
deleted = 0;
|
||||
mSleeping = 0;
|
||||
useSleep = 1;
|
||||
trbBodyIdx=0;
|
||||
mSleepCount=0;
|
||||
useCcd = 0;
|
||||
useContactCallback = 0;
|
||||
useSleepCallback = 0;
|
||||
linearDamping = 1.0f;
|
||||
angularDamping = 0.99f;
|
||||
}
|
||||
|
||||
#endif //BT_TRBSTATEVEC_H__
|
||||
|
||||
|
||||
/*
|
||||
Copyright (C) 2009 Sony Computer Entertainment Inc.
|
||||
All rights reserved.
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
|
||||
*/
|
||||
|
||||
#ifndef BT_TRBSTATEVEC_H__
|
||||
#define BT_TRBSTATEVEC_H__
|
||||
|
||||
#include <stdlib.h>
|
||||
#ifdef PFX_USE_FREE_VECTORMATH
|
||||
#include "vecmath/vmInclude.h"
|
||||
#else
|
||||
#include "vectormath/vmInclude.h"
|
||||
#endif //PFX_USE_FREE_VECTORMATH
|
||||
|
||||
|
||||
#include "PlatformDefinitions.h"
|
||||
|
||||
|
||||
static inline vmVector3 read_Vector3(const float* p)
|
||||
{
|
||||
vmVector3 v;
|
||||
loadXYZ(v, p);
|
||||
return v;
|
||||
}
|
||||
|
||||
static inline vmQuat read_Quat(const float* p)
|
||||
{
|
||||
vmQuat vq;
|
||||
loadXYZW(vq, p);
|
||||
return vq;
|
||||
}
|
||||
|
||||
static inline void store_Vector3(const vmVector3 &src, float* p)
|
||||
{
|
||||
vmVector3 v = src;
|
||||
storeXYZ(v, p);
|
||||
}
|
||||
|
||||
static inline void store_Quat(const vmQuat &src, float* p)
|
||||
{
|
||||
vmQuat vq = src;
|
||||
storeXYZW(vq, p);
|
||||
}
|
||||
|
||||
// Motion Type
|
||||
enum {
|
||||
PfxMotionTypeFixed = 0,
|
||||
PfxMotionTypeActive,
|
||||
PfxMotionTypeKeyframe,
|
||||
PfxMotionTypeOneWay,
|
||||
PfxMotionTypeTrigger,
|
||||
PfxMotionTypeCount
|
||||
};
|
||||
|
||||
#define PFX_MOTION_MASK_DYNAMIC 0x0a // Active,OneWay
|
||||
#define PFX_MOTION_MASK_STATIC 0x95 // Fixed,Keyframe,Trigger,Sleeping
|
||||
#define PFX_MOTION_MASK_SLEEP 0x0e // Can sleep
|
||||
#define PFX_MOTION_MASK_TYPE 0x7f
|
||||
|
||||
//
|
||||
// Rigid Body state
|
||||
//
|
||||
|
||||
#ifdef __CELLOS_LV2__
|
||||
ATTRIBUTE_ALIGNED128(class) TrbState
|
||||
#else
|
||||
ATTRIBUTE_ALIGNED16(class) TrbState
|
||||
#endif
|
||||
|
||||
{
|
||||
public:
|
||||
TrbState()
|
||||
{
|
||||
setMotionType(PfxMotionTypeActive);
|
||||
contactFilterSelf=contactFilterTarget=0xffffffff;
|
||||
deleted = 0;
|
||||
mSleeping = 0;
|
||||
useSleep = 1;
|
||||
trbBodyIdx=0;
|
||||
mSleepCount=0;
|
||||
useCcd = 0;
|
||||
useContactCallback = 0;
|
||||
useSleepCallback = 0;
|
||||
linearDamping = 1.0f;
|
||||
angularDamping = 0.99f;
|
||||
}
|
||||
|
||||
TrbState(const uint8_t m, const vmVector3& x, const vmQuat& q, const vmVector3& v, const vmVector3& omega );
|
||||
|
||||
uint16_t mSleepCount;
|
||||
uint8_t mMotionType;
|
||||
uint8_t deleted : 1;
|
||||
uint8_t mSleeping : 1;
|
||||
uint8_t useSleep : 1;
|
||||
uint8_t useCcd : 1;
|
||||
uint8_t useContactCallback : 1;
|
||||
uint8_t useSleepCallback : 1;
|
||||
|
||||
uint16_t trbBodyIdx;
|
||||
uint32_t contactFilterSelf;
|
||||
uint32_t contactFilterTarget;
|
||||
|
||||
float center[3]; // AABB center(World)
|
||||
float half[3]; // AABB half(World)
|
||||
|
||||
float linearDamping;
|
||||
float angularDamping;
|
||||
|
||||
float deltaLinearVelocity[3];
|
||||
float deltaAngularVelocity[3];
|
||||
|
||||
float fX[3]; // position
|
||||
float fQ[4]; // orientation
|
||||
float fV[3]; // velocity
|
||||
float fOmega[3]; // angular velocity
|
||||
|
||||
inline void setZero(); // Zeroes out the elements
|
||||
inline void setIdentity(); // Sets the rotation to identity and zeroes out the other elements
|
||||
|
||||
bool isDeleted() const {return deleted==1;}
|
||||
|
||||
uint16_t getRigidBodyId() const {return trbBodyIdx;}
|
||||
void setRigidBodyId(uint16_t i) {trbBodyIdx = i;}
|
||||
|
||||
|
||||
uint32_t getContactFilterSelf() const {return contactFilterSelf;}
|
||||
void setContactFilterSelf(uint32_t filter) {contactFilterSelf = filter;}
|
||||
|
||||
uint32_t getContactFilterTarget() const {return contactFilterTarget;}
|
||||
void setContactFilterTarget(uint32_t filter) {contactFilterTarget = filter;}
|
||||
|
||||
float getLinearDamping() const {return linearDamping;}
|
||||
float getAngularDamping() const {return angularDamping;}
|
||||
|
||||
void setLinearDamping(float damping) {linearDamping=damping;}
|
||||
void setAngularDamping(float damping) {angularDamping=damping;}
|
||||
|
||||
|
||||
uint8_t getMotionType() const {return mMotionType;}
|
||||
void setMotionType(uint8_t t) {mMotionType = t;mSleeping=0;mSleepCount=0;}
|
||||
|
||||
uint8_t getMotionMask() const {return (1<<mMotionType)|(mSleeping<<7);}
|
||||
|
||||
bool isAsleep() const {return mSleeping==1;}
|
||||
bool isAwake() const {return mSleeping==0;}
|
||||
|
||||
void wakeup() {mSleeping=0;mSleepCount=0;}
|
||||
void sleep() {if(useSleep) {mSleeping=1;mSleepCount=0;}}
|
||||
|
||||
uint8_t getUseSleep() const {return useSleep;}
|
||||
void setUseSleep(uint8_t b) {useSleep=b;}
|
||||
|
||||
uint8_t getUseCcd() const {return useCcd;}
|
||||
void setUseCcd(uint8_t b) {useCcd=b;}
|
||||
|
||||
uint8_t getUseContactCallback() const {return useContactCallback;}
|
||||
void setUseContactCallback(uint8_t b) {useContactCallback=b;}
|
||||
|
||||
uint8_t getUseSleepCallback() const {return useSleepCallback;}
|
||||
void setUseSleepCallback(uint8_t b) {useSleepCallback=b;}
|
||||
|
||||
void incrementSleepCount() {mSleepCount++;}
|
||||
void resetSleepCount() {mSleepCount=0;}
|
||||
uint16_t getSleepCount() const {return mSleepCount;}
|
||||
|
||||
vmVector3 getPosition() const {return read_Vector3(fX);}
|
||||
vmQuat getOrientation() const {return read_Quat(fQ);}
|
||||
vmVector3 getLinearVelocity() const {return read_Vector3(fV);}
|
||||
vmVector3 getAngularVelocity() const {return read_Vector3(fOmega);}
|
||||
vmVector3 getDeltaLinearVelocity() const {return read_Vector3(deltaLinearVelocity);}
|
||||
vmVector3 getDeltaAngularVelocity() const {return read_Vector3(deltaAngularVelocity);}
|
||||
|
||||
void setPosition(const vmVector3 &pos) {store_Vector3(pos, fX);}
|
||||
void setLinearVelocity(const vmVector3 &vel) {store_Vector3(vel, fV);}
|
||||
void setAngularVelocity(const vmVector3 &vel) {store_Vector3(vel, fOmega);}
|
||||
void setDeltaLinearVelocity(const vmVector3 &vel) {store_Vector3(vel, deltaLinearVelocity);}
|
||||
void setDeltaAngularVelocity(const vmVector3 &vel) {store_Vector3(vel, deltaAngularVelocity);}
|
||||
void setOrientation(const vmQuat &rot) {store_Quat(rot, fQ);}
|
||||
|
||||
inline void setAuxils(const vmVector3 ¢erLocal,const vmVector3 &halfLocal);
|
||||
inline void setAuxilsCcd(const vmVector3 ¢erLocal,const vmVector3 &halfLocal,float timeStep);
|
||||
inline void reset();
|
||||
};
|
||||
|
||||
inline
|
||||
TrbState::TrbState(const uint8_t m, const vmVector3& x, const vmQuat& q, const vmVector3& v, const vmVector3& omega)
|
||||
{
|
||||
setMotionType(m);
|
||||
fX[0] = x[0];
|
||||
fX[1] = x[1];
|
||||
fX[2] = x[2];
|
||||
fQ[0] = q[0];
|
||||
fQ[1] = q[1];
|
||||
fQ[2] = q[2];
|
||||
fQ[3] = q[3];
|
||||
fV[0] = v[0];
|
||||
fV[1] = v[1];
|
||||
fV[2] = v[2];
|
||||
fOmega[0] = omega[0];
|
||||
fOmega[1] = omega[1];
|
||||
fOmega[2] = omega[2];
|
||||
contactFilterSelf=contactFilterTarget=0xffff;
|
||||
trbBodyIdx=0;
|
||||
mSleeping = 0;
|
||||
deleted = 0;
|
||||
useSleep = 1;
|
||||
useCcd = 0;
|
||||
useContactCallback = 0;
|
||||
useSleepCallback = 0;
|
||||
mSleepCount=0;
|
||||
linearDamping = 1.0f;
|
||||
angularDamping = 0.99f;
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setIdentity()
|
||||
{
|
||||
fX[0] = 0.0f;
|
||||
fX[1] = 0.0f;
|
||||
fX[2] = 0.0f;
|
||||
fQ[0] = 0.0f;
|
||||
fQ[1] = 0.0f;
|
||||
fQ[2] = 0.0f;
|
||||
fQ[3] = 1.0f;
|
||||
fV[0] = 0.0f;
|
||||
fV[1] = 0.0f;
|
||||
fV[2] = 0.0f;
|
||||
fOmega[0] = 0.0f;
|
||||
fOmega[1] = 0.0f;
|
||||
fOmega[2] = 0.0f;
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setZero()
|
||||
{
|
||||
fX[0] = 0.0f;
|
||||
fX[1] = 0.0f;
|
||||
fX[2] = 0.0f;
|
||||
fQ[0] = 0.0f;
|
||||
fQ[1] = 0.0f;
|
||||
fQ[2] = 0.0f;
|
||||
fQ[3] = 0.0f;
|
||||
fV[0] = 0.0f;
|
||||
fV[1] = 0.0f;
|
||||
fV[2] = 0.0f;
|
||||
fOmega[0] = 0.0f;
|
||||
fOmega[1] = 0.0f;
|
||||
fOmega[2] = 0.0f;
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setAuxils(const vmVector3 ¢erLocal,const vmVector3 &halfLocal)
|
||||
{
|
||||
vmVector3 centerW = getPosition() + rotate(getOrientation(),centerLocal);
|
||||
vmVector3 halfW = absPerElem(vmMatrix3(getOrientation())) * halfLocal;
|
||||
center[0] = centerW[0];
|
||||
center[1] = centerW[1];
|
||||
center[2] = centerW[2];
|
||||
half[0] = halfW[0];
|
||||
half[1] = halfW[1];
|
||||
half[2] = halfW[2];
|
||||
}
|
||||
|
||||
inline void
|
||||
TrbState::setAuxilsCcd(const vmVector3 ¢erLocal,const vmVector3 &halfLocal,float timeStep)
|
||||
{
|
||||
vmVector3 centerW = getPosition() + rotate(getOrientation(),centerLocal);
|
||||
vmVector3 halfW = absPerElem(vmMatrix3(getOrientation())) * halfLocal;
|
||||
|
||||
vmVector3 diffvec = getLinearVelocity()*timeStep;
|
||||
|
||||
vmVector3 newCenter = centerW + diffvec;
|
||||
vmVector3 aabbMin = minPerElem(newCenter - halfW,centerW - halfW);
|
||||
vmVector3 aabbMax = maxPerElem(newCenter + halfW,centerW + halfW);
|
||||
|
||||
centerW = 0.5f * (aabbMin + aabbMax);
|
||||
halfW =0.5f * (aabbMax - aabbMin);
|
||||
|
||||
center[0] = centerW[0];
|
||||
center[1] = centerW[1];
|
||||
center[2] = centerW[2];
|
||||
|
||||
half[0] = halfW[0];
|
||||
half[1] = halfW[1];
|
||||
half[2] = halfW[2];
|
||||
}
|
||||
|
||||
inline
|
||||
void TrbState::reset()
|
||||
{
|
||||
#if 0
|
||||
mSleepCount = 0;
|
||||
mMotionType = PfxMotionTypeActive;
|
||||
mDeleted = 0;
|
||||
mSleeping = 0;
|
||||
mUseSleep = 1;
|
||||
mUseCcd = 0;
|
||||
mUseContactCallback = 0;
|
||||
mUseSleepCallback = 0;
|
||||
mRigidBodyId = 0;
|
||||
mContactFilterSelf = 0xffffffff;
|
||||
mContactFilterTarget = 0xffffffff;
|
||||
mLinearDamping = 1.0f;
|
||||
mAngularDamping = 0.99f;
|
||||
mPosition = vmVector3(0.0f);
|
||||
mOrientation = vmQuat::identity();
|
||||
mLinearVelocity = vmVector3(0.0f);
|
||||
mAngularVelocity = vmVector3(0.0f);
|
||||
#endif
|
||||
|
||||
setMotionType(PfxMotionTypeActive);
|
||||
contactFilterSelf=contactFilterTarget=0xffffffff;
|
||||
deleted = 0;
|
||||
mSleeping = 0;
|
||||
useSleep = 1;
|
||||
trbBodyIdx=0;
|
||||
mSleepCount=0;
|
||||
useCcd = 0;
|
||||
useContactCallback = 0;
|
||||
useSleepCallback = 0;
|
||||
linearDamping = 1.0f;
|
||||
angularDamping = 0.99f;
|
||||
}
|
||||
|
||||
#endif //BT_TRBSTATEVEC_H__
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user