merged most of the changes from the branch into trunk, except for COLLADA, libxml and glut glitches.
Still need to verify to make sure no unwanted renaming is introduced.
This commit is contained in:
@@ -21,14 +21,14 @@ subject to the following restrictions:
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "CcdPhysicsEnvironment.h"
|
||||
#include "LinearMath/SimdTransformUtil.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btConeShape.h"
|
||||
|
||||
class BP_Proxy;
|
||||
|
||||
///todo: fill all the empty CcdPhysicsController methods, hook them up to the RigidBody class
|
||||
///todo: fill all the empty CcdPhysicsController methods, hook them up to the btRigidBody class
|
||||
|
||||
//'temporarily' global variables
|
||||
float gDeactivationTime = 2.f;
|
||||
@@ -39,8 +39,8 @@ float gAngularSleepingTreshold = 1.0f;
|
||||
|
||||
#include "BulletDynamics/Dynamics/btMassProps.h"
|
||||
|
||||
SimdVector3 startVel(0,0,0);//-10000);
|
||||
CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
|
||||
btVector3 startVel(0,0,0);//-10000);
|
||||
CcdPhysicsController::CcdPhysicsController (const btCcdConstructionInfo& ci)
|
||||
:m_cci(ci)
|
||||
{
|
||||
m_collisionDelay = 0;
|
||||
@@ -61,14 +61,14 @@ CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
|
||||
|
||||
}
|
||||
|
||||
SimdTransform CcdPhysicsController::GetTransformFromMotionState(PHY_IMotionState* motionState)
|
||||
btTransform CcdPhysicsController::GetTransformFromMotionState(PHY_IMotionState* motionState)
|
||||
{
|
||||
SimdTransform trans;
|
||||
btTransform trans;
|
||||
float tmp[3];
|
||||
motionState->getWorldPosition(tmp[0],tmp[1],tmp[2]);
|
||||
trans.setOrigin(SimdVector3(tmp[0],tmp[1],tmp[2]));
|
||||
trans.setOrigin(btVector3(tmp[0],tmp[1],tmp[2]));
|
||||
|
||||
SimdQuaternion orn;
|
||||
btQuaternion orn;
|
||||
motionState->getWorldOrientation(orn[0],orn[1],orn[2],orn[3]);
|
||||
trans.setRotation(orn);
|
||||
return trans;
|
||||
@@ -78,11 +78,11 @@ SimdTransform CcdPhysicsController::GetTransformFromMotionState(PHY_IMotionState
|
||||
void CcdPhysicsController::CreateRigidbody()
|
||||
{
|
||||
|
||||
SimdTransform trans = GetTransformFromMotionState(m_cci.m_MotionState);
|
||||
btTransform trans = GetTransformFromMotionState(m_cci.m_MotionState);
|
||||
|
||||
MassProps mp(m_cci.m_mass, m_cci.m_localInertiaTensor);
|
||||
btMassProps mp(m_cci.m_mass, m_cci.m_localInertiaTensor);
|
||||
|
||||
m_body = new RigidBody(mp,0,0,m_cci.m_friction,m_cci.m_restitution);
|
||||
m_body = new btRigidBody(mp,0,0,m_cci.m_friction,m_cci.m_restitution);
|
||||
m_body->m_collisionShape = m_cci.m_collisionShape;
|
||||
|
||||
|
||||
@@ -120,27 +120,27 @@ bool CcdPhysicsController::SynchronizeMotionStates(float time)
|
||||
|
||||
if (!m_body->IsStatic())
|
||||
{
|
||||
const SimdVector3& worldPos = m_body->getCenterOfMassPosition();
|
||||
const btVector3& worldPos = m_body->getCenterOfMassPosition();
|
||||
m_MotionState->setWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
|
||||
|
||||
const SimdQuaternion& worldquat = m_body->getOrientation();
|
||||
const btQuaternion& worldquat = m_body->getOrientation();
|
||||
m_MotionState->setWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
|
||||
|
||||
m_MotionState->calculateWorldTransformations();
|
||||
|
||||
float scale[3];
|
||||
m_MotionState->getWorldScaling(scale[0],scale[1],scale[2]);
|
||||
SimdVector3 scaling(scale[0],scale[1],scale[2]);
|
||||
btVector3 scaling(scale[0],scale[1],scale[2]);
|
||||
GetCollisionShape()->setLocalScaling(scaling);
|
||||
} else
|
||||
{
|
||||
SimdVector3 worldPos;
|
||||
SimdQuaternion worldquat;
|
||||
btVector3 worldPos;
|
||||
btQuaternion worldquat;
|
||||
|
||||
m_MotionState->getWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
|
||||
m_MotionState->getWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
|
||||
SimdTransform oldTrans = m_body->getCenterOfMassTransform();
|
||||
SimdTransform newTrans(worldquat,worldPos);
|
||||
btTransform oldTrans = m_body->getCenterOfMassTransform();
|
||||
btTransform newTrans(worldquat,worldPos);
|
||||
|
||||
m_body->setCenterOfMassTransform(newTrans);
|
||||
//need to keep track of previous position for friction effects...
|
||||
@@ -149,7 +149,7 @@ bool CcdPhysicsController::SynchronizeMotionStates(float time)
|
||||
|
||||
float scale[3];
|
||||
m_MotionState->getWorldScaling(scale[0],scale[1],scale[2]);
|
||||
SimdVector3 scaling(scale[0],scale[1],scale[2]);
|
||||
btVector3 scaling(scale[0],scale[1],scale[2]);
|
||||
GetCollisionShape()->setLocalScaling(scaling);
|
||||
}
|
||||
return true;
|
||||
@@ -219,8 +219,8 @@ void CcdPhysicsController::RelativeTranslate(float dlocX,float dlocY,float dloc
|
||||
{
|
||||
m_body->activate();
|
||||
|
||||
SimdVector3 dloc(dlocX,dlocY,dlocZ);
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
btVector3 dloc(dlocX,dlocY,dlocZ);
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
|
||||
if (local)
|
||||
{
|
||||
@@ -239,15 +239,15 @@ void CcdPhysicsController::RelativeRotate(const float rotval[9],bool local)
|
||||
{
|
||||
m_body->activate();
|
||||
|
||||
SimdMatrix3x3 drotmat( rotval[0],rotval[1],rotval[2],
|
||||
btMatrix3x3 drotmat( rotval[0],rotval[1],rotval[2],
|
||||
rotval[4],rotval[5],rotval[6],
|
||||
rotval[8],rotval[9],rotval[10]);
|
||||
|
||||
|
||||
SimdMatrix3x3 currentOrn;
|
||||
btMatrix3x3 currentOrn;
|
||||
GetWorldOrientation(currentOrn);
|
||||
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
|
||||
xform.setBasis(xform.getBasis()*(local ?
|
||||
drotmat : (currentOrn.inverse() * drotmat * currentOrn)));
|
||||
@@ -257,17 +257,17 @@ void CcdPhysicsController::RelativeRotate(const float rotval[9],bool local)
|
||||
|
||||
}
|
||||
|
||||
void CcdPhysicsController::GetWorldOrientation(SimdMatrix3x3& mat)
|
||||
void CcdPhysicsController::GetWorldOrientation(btMatrix3x3& mat)
|
||||
{
|
||||
float orn[4];
|
||||
m_MotionState->getWorldOrientation(orn[0],orn[1],orn[2],orn[3]);
|
||||
SimdQuaternion quat(orn[0],orn[1],orn[2],orn[3]);
|
||||
btQuaternion quat(orn[0],orn[1],orn[2],orn[3]);
|
||||
mat.setRotation(quat);
|
||||
}
|
||||
|
||||
void CcdPhysicsController::getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal)
|
||||
{
|
||||
SimdQuaternion q = m_body->getCenterOfMassTransform().getRotation();
|
||||
btQuaternion q = m_body->getCenterOfMassTransform().getRotation();
|
||||
quatImag0 = q[0];
|
||||
quatImag1 = q[1];
|
||||
quatImag2 = q[2];
|
||||
@@ -277,8 +277,8 @@ void CcdPhysicsController::setOrientation(float quatImag0,float quatImag1,float
|
||||
{
|
||||
m_body->activate();
|
||||
m_MotionState->setWorldOrientation(quatImag0,quatImag1,quatImag2,quatReal);
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
xform.setRotation(SimdQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
xform.setRotation(btQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
|
||||
m_body->setCenterOfMassTransform(xform);
|
||||
|
||||
}
|
||||
@@ -287,8 +287,8 @@ void CcdPhysicsController::setPosition(float posX,float posY,float posZ)
|
||||
{
|
||||
m_body->activate();
|
||||
m_MotionState->setWorldPosition(posX,posY,posZ);
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
xform.setOrigin(SimdVector3(posX,posY,posZ));
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
xform.setOrigin(btVector3(posX,posY,posZ));
|
||||
m_body->setCenterOfMassTransform(xform);
|
||||
|
||||
}
|
||||
@@ -298,7 +298,7 @@ void CcdPhysicsController::resolveCombinedVelocities(float linvelX,float linvel
|
||||
|
||||
void CcdPhysicsController::getPosition(PHY__Vector3& pos) const
|
||||
{
|
||||
const SimdTransform& xform = m_body->getCenterOfMassTransform();
|
||||
const btTransform& xform = m_body->getCenterOfMassTransform();
|
||||
pos[0] = xform.getOrigin().x();
|
||||
pos[1] = xform.getOrigin().y();
|
||||
pos[2] = xform.getOrigin().z();
|
||||
@@ -306,11 +306,11 @@ void CcdPhysicsController::getPosition(PHY__Vector3& pos) const
|
||||
|
||||
void CcdPhysicsController::setScaling(float scaleX,float scaleY,float scaleZ)
|
||||
{
|
||||
if (!SimdFuzzyZero(m_cci.m_scaling.x()-scaleX) ||
|
||||
!SimdFuzzyZero(m_cci.m_scaling.y()-scaleY) ||
|
||||
!SimdFuzzyZero(m_cci.m_scaling.z()-scaleZ))
|
||||
if (!btFuzzyZero(m_cci.m_scaling.x()-scaleX) ||
|
||||
!btFuzzyZero(m_cci.m_scaling.y()-scaleY) ||
|
||||
!btFuzzyZero(m_cci.m_scaling.z()-scaleZ))
|
||||
{
|
||||
m_cci.m_scaling = SimdVector3(scaleX,scaleY,scaleZ);
|
||||
m_cci.m_scaling = btVector3(scaleX,scaleY,scaleZ);
|
||||
|
||||
if (m_body && m_body->GetCollisionShape())
|
||||
{
|
||||
@@ -324,8 +324,8 @@ void CcdPhysicsController::setScaling(float scaleX,float scaleY,float scaleZ)
|
||||
// physics methods
|
||||
void CcdPhysicsController::ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local)
|
||||
{
|
||||
SimdVector3 torque(torqueX,torqueY,torqueZ);
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
btVector3 torque(torqueX,torqueY,torqueZ);
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
if (local)
|
||||
{
|
||||
torque = xform.getBasis()*torque;
|
||||
@@ -335,8 +335,8 @@ void CcdPhysicsController::ApplyTorque(float torqueX,float torqueY,float torque
|
||||
|
||||
void CcdPhysicsController::ApplyForce(float forceX,float forceY,float forceZ,bool local)
|
||||
{
|
||||
SimdVector3 force(forceX,forceY,forceZ);
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
btVector3 force(forceX,forceY,forceZ);
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
if (local)
|
||||
{
|
||||
force = xform.getBasis()*force;
|
||||
@@ -345,14 +345,14 @@ void CcdPhysicsController::ApplyForce(float forceX,float forceY,float forceZ,bo
|
||||
}
|
||||
void CcdPhysicsController::SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local)
|
||||
{
|
||||
SimdVector3 angvel(ang_velX,ang_velY,ang_velZ);
|
||||
btVector3 angvel(ang_velX,ang_velY,ang_velZ);
|
||||
if (angvel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
|
||||
{
|
||||
m_body->activate();
|
||||
}
|
||||
|
||||
{
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
if (local)
|
||||
{
|
||||
angvel = xform.getBasis()*angvel;
|
||||
@@ -365,14 +365,14 @@ void CcdPhysicsController::SetAngularVelocity(float ang_velX,float ang_velY,flo
|
||||
void CcdPhysicsController::SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local)
|
||||
{
|
||||
|
||||
SimdVector3 linVel(lin_velX,lin_velY,lin_velZ);
|
||||
btVector3 linVel(lin_velX,lin_velY,lin_velZ);
|
||||
if (linVel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
|
||||
{
|
||||
m_body->activate();
|
||||
}
|
||||
|
||||
{
|
||||
SimdTransform xform = m_body->getCenterOfMassTransform();
|
||||
btTransform xform = m_body->getCenterOfMassTransform();
|
||||
if (local)
|
||||
{
|
||||
linVel = xform.getBasis()*linVel;
|
||||
@@ -382,13 +382,13 @@ void CcdPhysicsController::SetLinearVelocity(float lin_velX,float lin_velY,floa
|
||||
}
|
||||
void CcdPhysicsController::applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ)
|
||||
{
|
||||
SimdVector3 impulse(impulseX,impulseY,impulseZ);
|
||||
btVector3 impulse(impulseX,impulseY,impulseZ);
|
||||
|
||||
if (impulse.length2() > (SIMD_EPSILON*SIMD_EPSILON))
|
||||
{
|
||||
m_body->activate();
|
||||
|
||||
SimdVector3 pos(attachX,attachY,attachZ);
|
||||
btVector3 pos(attachX,attachY,attachZ);
|
||||
|
||||
m_body->activate();
|
||||
|
||||
@@ -402,7 +402,7 @@ void CcdPhysicsController::SetActive(bool active)
|
||||
// reading out information from physics
|
||||
void CcdPhysicsController::GetLinearVelocity(float& linvX,float& linvY,float& linvZ)
|
||||
{
|
||||
const SimdVector3& linvel = this->m_body->getLinearVelocity();
|
||||
const btVector3& linvel = this->m_body->getLinearVelocity();
|
||||
linvX = linvel.x();
|
||||
linvY = linvel.y();
|
||||
linvZ = linvel.z();
|
||||
@@ -411,7 +411,7 @@ void CcdPhysicsController::GetLinearVelocity(float& linvX,float& linvY,float& l
|
||||
|
||||
void CcdPhysicsController::GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ)
|
||||
{
|
||||
const SimdVector3& angvel= m_body->getAngularVelocity();
|
||||
const btVector3& angvel= m_body->getAngularVelocity();
|
||||
angVelX = angvel.x();
|
||||
angVelY = angvel.y();
|
||||
angVelZ = angvel.z();
|
||||
@@ -419,9 +419,9 @@ void CcdPhysicsController::GetAngularVelocity(float& angVelX,float& angVelY,flo
|
||||
|
||||
void CcdPhysicsController::GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ)
|
||||
{
|
||||
SimdVector3 pos(posX,posY,posZ);
|
||||
SimdVector3 rel_pos = pos-m_body->getCenterOfMassPosition();
|
||||
SimdVector3 linvel = m_body->getVelocityInLocalPoint(rel_pos);
|
||||
btVector3 pos(posX,posY,posZ);
|
||||
btVector3 rel_pos = pos-m_body->getCenterOfMassPosition();
|
||||
btVector3 linvel = m_body->getVelocityInLocalPoint(rel_pos);
|
||||
linvX = linvel.x();
|
||||
linvY = linvel.y();
|
||||
linvZ = linvel.z();
|
||||
@@ -436,7 +436,7 @@ void CcdPhysicsController::setRigidBody(bool rigid)
|
||||
if (!rigid)
|
||||
{
|
||||
//fake it for now
|
||||
SimdVector3 inertia = m_body->getInvInertiaDiagLocal();
|
||||
btVector3 inertia = m_body->getInvInertiaDiagLocal();
|
||||
inertia[1] = 0.f;
|
||||
m_body->setInvInertiaDiagLocal(inertia);
|
||||
m_body->updateInertiaTensor();
|
||||
@@ -494,24 +494,24 @@ bool CcdPhysicsController::wantsSleeping()
|
||||
PHY_IPhysicsController* CcdPhysicsController::GetReplica()
|
||||
{
|
||||
//very experimental, shape sharing is not implemented yet.
|
||||
//just support SphereShape/ConeShape for now
|
||||
//just support btSphereShape/ConeShape for now
|
||||
|
||||
CcdConstructionInfo cinfo = m_cci;
|
||||
btCcdConstructionInfo cinfo = m_cci;
|
||||
if (cinfo.m_collisionShape)
|
||||
{
|
||||
switch (cinfo.m_collisionShape->GetShapeType())
|
||||
{
|
||||
case SPHERE_SHAPE_PROXYTYPE:
|
||||
{
|
||||
SphereShape* orgShape = (SphereShape*)cinfo.m_collisionShape;
|
||||
cinfo.m_collisionShape = new SphereShape(*orgShape);
|
||||
btSphereShape* orgShape = (btSphereShape*)cinfo.m_collisionShape;
|
||||
cinfo.m_collisionShape = new btSphereShape(*orgShape);
|
||||
break;
|
||||
}
|
||||
|
||||
case CONE_SHAPE_PROXYTYPE:
|
||||
{
|
||||
ConeShape* orgShape = (ConeShape*)cinfo.m_collisionShape;
|
||||
cinfo.m_collisionShape = new ConeShape(*orgShape);
|
||||
btConeShape* orgShape = (btConeShape*)cinfo.m_collisionShape;
|
||||
cinfo.m_collisionShape = new btConeShape(*orgShape);
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -570,13 +570,13 @@ void DefaultMotionState::getWorldOrientation(float& quatIma0,float& quatIma1,flo
|
||||
|
||||
void DefaultMotionState::setWorldPosition(float posX,float posY,float posZ)
|
||||
{
|
||||
SimdPoint3 pos(posX,posY,posZ);
|
||||
btPoint3 pos(posX,posY,posZ);
|
||||
m_worldTransform.setOrigin( pos );
|
||||
}
|
||||
|
||||
void DefaultMotionState::setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal)
|
||||
{
|
||||
SimdQuaternion orn(quatIma0,quatIma1,quatIma2,quatReal);
|
||||
btQuaternion orn(quatIma0,quatIma1,quatIma2,quatReal);
|
||||
m_worldTransform.setRotation( orn );
|
||||
}
|
||||
|
||||
|
||||
@@ -21,16 +21,16 @@ subject to the following restrictions:
|
||||
|
||||
/// PHY_IPhysicsController is the abstract simplified Interface to a physical object.
|
||||
/// It contains the IMotionState and IDeformableMesh Interfaces.
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdScalar.h"
|
||||
#include "LinearMath/SimdMatrix3x3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "LinearMath/btVector3.h"
|
||||
#include "LinearMath/btScalar.h"
|
||||
#include "LinearMath/btMatrix3x3.h"
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
|
||||
#include "PHY_IMotionState.h"
|
||||
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" //for CollisionShape access
|
||||
class CollisionShape;
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" //for btCollisionShape access
|
||||
class btCollisionShape;
|
||||
|
||||
extern float gDeactivationTime;
|
||||
extern float gLinearSleepingTreshold;
|
||||
@@ -41,12 +41,12 @@ class CcdPhysicsEnvironment;
|
||||
|
||||
|
||||
|
||||
struct CcdConstructionInfo
|
||||
struct btCcdConstructionInfo
|
||||
{
|
||||
|
||||
///CollisionFilterGroups provides some optional usage of basic collision filtering
|
||||
///this is done during broadphase, so very early in the pipeline
|
||||
///more advanced collision filtering should be done in CollisionDispatcher::NeedsCollision
|
||||
///more advanced collision filtering should be done in btCollisionDispatcher::NeedsCollision
|
||||
enum CollisionFilterGroups
|
||||
{
|
||||
DefaultFilter = 1,
|
||||
@@ -57,7 +57,7 @@ struct CcdConstructionInfo
|
||||
};
|
||||
|
||||
|
||||
CcdConstructionInfo()
|
||||
btCcdConstructionInfo()
|
||||
: m_gravity(0,0,0),
|
||||
m_scaling(1.f,1.f,1.f),
|
||||
m_mass(0.f),
|
||||
@@ -74,26 +74,26 @@ struct CcdConstructionInfo
|
||||
{
|
||||
}
|
||||
|
||||
SimdVector3 m_localInertiaTensor;
|
||||
SimdVector3 m_gravity;
|
||||
SimdVector3 m_scaling;
|
||||
SimdScalar m_mass;
|
||||
SimdScalar m_restitution;
|
||||
SimdScalar m_friction;
|
||||
SimdScalar m_linearDamping;
|
||||
SimdScalar m_angularDamping;
|
||||
btVector3 m_localInertiaTensor;
|
||||
btVector3 m_gravity;
|
||||
btVector3 m_scaling;
|
||||
btScalar m_mass;
|
||||
btScalar m_restitution;
|
||||
btScalar m_friction;
|
||||
btScalar m_linearDamping;
|
||||
btScalar m_angularDamping;
|
||||
int m_collisionFlags;
|
||||
|
||||
///optional use of collision group/mask:
|
||||
///only collision with object goups that match the collision mask.
|
||||
///this is very basic early out. advanced collision filtering should be
|
||||
///done in the CollisionDispatcher::NeedsCollision and NeedsResponse
|
||||
///done in the btCollisionDispatcher::NeedsCollision and NeedsResponse
|
||||
///both values default to 1
|
||||
short int m_collisionFilterGroup;
|
||||
short int m_collisionFilterMask;
|
||||
|
||||
|
||||
CollisionShape* m_collisionShape;
|
||||
btCollisionShape* m_collisionShape;
|
||||
class PHY_IMotionState* m_MotionState;
|
||||
|
||||
CcdPhysicsEnvironment* m_physicsEnv; //needed for self-replication
|
||||
@@ -101,19 +101,19 @@ struct CcdConstructionInfo
|
||||
};
|
||||
|
||||
|
||||
class RigidBody;
|
||||
class btRigidBody;
|
||||
|
||||
///CcdPhysicsController is a physics object that supports continuous collision detection and time of impact based physics resolution.
|
||||
class CcdPhysicsController : public PHY_IPhysicsController
|
||||
{
|
||||
RigidBody* m_body;
|
||||
btRigidBody* m_body;
|
||||
class PHY_IMotionState* m_MotionState;
|
||||
|
||||
|
||||
void* m_newClientInfo;
|
||||
|
||||
CcdConstructionInfo m_cci;//needed for replication
|
||||
void GetWorldOrientation(SimdMatrix3x3& mat);
|
||||
btCcdConstructionInfo m_cci;//needed for replication
|
||||
void GetWorldOrientation(btMatrix3x3& mat);
|
||||
|
||||
void CreateRigidbody();
|
||||
|
||||
@@ -122,14 +122,14 @@ class CcdPhysicsController : public PHY_IPhysicsController
|
||||
int m_collisionDelay;
|
||||
|
||||
|
||||
CcdPhysicsController (const CcdConstructionInfo& ci);
|
||||
CcdPhysicsController (const btCcdConstructionInfo& ci);
|
||||
|
||||
virtual ~CcdPhysicsController();
|
||||
|
||||
|
||||
RigidBody* GetRigidBody() { return m_body;}
|
||||
btRigidBody* GetRigidBody() { return m_body;}
|
||||
|
||||
CollisionShape* GetCollisionShape() {
|
||||
btCollisionShape* GetCollisionShape() {
|
||||
return m_body->GetCollisionShape();
|
||||
}
|
||||
////////////////////////////////////
|
||||
@@ -206,9 +206,9 @@ class CcdPhysicsController : public PHY_IPhysicsController
|
||||
|
||||
void UpdateDeactivation(float timeStep);
|
||||
|
||||
static SimdTransform GetTransformFromMotionState(PHY_IMotionState* motionState);
|
||||
static btTransform GetTransformFromMotionState(PHY_IMotionState* motionState);
|
||||
|
||||
void SetAabb(const SimdVector3& aabbMin,const SimdVector3& aabbMax);
|
||||
void SetAabb(const btVector3& aabbMin,const btVector3& aabbMax);
|
||||
|
||||
|
||||
class PHY_IMotionState* GetMotionState()
|
||||
@@ -227,7 +227,7 @@ class CcdPhysicsController : public PHY_IPhysicsController
|
||||
|
||||
|
||||
|
||||
///DefaultMotionState implements standard motionstate, using SimdTransform
|
||||
///DefaultMotionState implements standard motionstate, using btTransform
|
||||
class DefaultMotionState : public PHY_IMotionState
|
||||
|
||||
{
|
||||
@@ -245,8 +245,8 @@ class DefaultMotionState : public PHY_IMotionState
|
||||
|
||||
virtual void calculateWorldTransformations();
|
||||
|
||||
SimdTransform m_worldTransform;
|
||||
SimdVector3 m_localScaling;
|
||||
btTransform m_worldTransform;
|
||||
btVector3 m_localScaling;
|
||||
|
||||
};
|
||||
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -19,16 +19,16 @@ subject to the following restrictions:
|
||||
#include "PHY_IPhysicsEnvironment.h"
|
||||
#include <vector>
|
||||
class CcdPhysicsController;
|
||||
#include "LinearMath/SimdVector3.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "LinearMath/btVector3.h"
|
||||
#include "LinearMath/btTransform.h"
|
||||
|
||||
|
||||
|
||||
|
||||
class TypedConstraint;
|
||||
class SimulationIslandManager;
|
||||
class CollisionDispatcher;
|
||||
class Dispatcher;
|
||||
class btTypedConstraint;
|
||||
class btSimulationIslandManager;
|
||||
class btCollisionDispatcher;
|
||||
class btDispatcher;
|
||||
//#include "btBroadphaseInterface.h"
|
||||
|
||||
//switch on/off new vehicle support
|
||||
@@ -37,10 +37,10 @@ class Dispatcher;
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
|
||||
class WrapperVehicle;
|
||||
class PersistentManifold;
|
||||
class BroadphaseInterface;
|
||||
class OverlappingPairCache;
|
||||
class IDebugDraw;
|
||||
class btPersistentManifold;
|
||||
class btBroadphaseInterface;
|
||||
class btOverlappingPairCache;
|
||||
class btIDebugDraw;
|
||||
class PHY_IVehicle;
|
||||
|
||||
/// CcdPhysicsEnvironment is an experimental mainloop for physics simulation using optional continuous collision detection.
|
||||
@@ -49,12 +49,12 @@ class PHY_IVehicle;
|
||||
/// A derived class may be able to 'construct' entities by loading and/or converting
|
||||
class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
|
||||
{
|
||||
SimdVector3 m_gravity;
|
||||
btVector3 m_gravity;
|
||||
|
||||
|
||||
|
||||
protected:
|
||||
IDebugDraw* m_debugDrawer;
|
||||
btIDebugDraw* m_debugDrawer;
|
||||
//solver iterations
|
||||
int m_numIterations;
|
||||
|
||||
@@ -67,12 +67,12 @@ protected:
|
||||
int m_profileTimings;
|
||||
bool m_enableSatCollisionDetection;
|
||||
|
||||
ContactSolverInfo m_solverInfo;
|
||||
btContactSolverInfo m_solverInfo;
|
||||
|
||||
SimulationIslandManager* m_islandManager;
|
||||
btSimulationIslandManager* m_islandManager;
|
||||
|
||||
public:
|
||||
CcdPhysicsEnvironment(Dispatcher* dispatcher=0, OverlappingPairCache* pairCache=0);
|
||||
CcdPhysicsEnvironment(btDispatcher* dispatcher=0, btOverlappingPairCache* pairCache=0);
|
||||
|
||||
virtual ~CcdPhysicsEnvironment();
|
||||
|
||||
@@ -82,7 +82,7 @@ protected:
|
||||
|
||||
/// Perform an integration step of duration 'timeStep'.
|
||||
|
||||
virtual void setDebugDrawer(IDebugDraw* debugDrawer)
|
||||
virtual void setDebugDrawer(btIDebugDraw* debugDrawer)
|
||||
{
|
||||
m_debugDrawer = debugDrawer;
|
||||
}
|
||||
@@ -127,12 +127,12 @@ protected:
|
||||
//Following the COLLADA physics specification for constraints
|
||||
virtual int createUniversalD6Constraint(
|
||||
class PHY_IPhysicsController* ctrlRef,class PHY_IPhysicsController* ctrlOther,
|
||||
SimdTransform& localAttachmentFrameRef,
|
||||
SimdTransform& localAttachmentOther,
|
||||
const SimdVector3& linearMinLimits,
|
||||
const SimdVector3& linearMaxLimits,
|
||||
const SimdVector3& angularMinLimits,
|
||||
const SimdVector3& angularMaxLimits
|
||||
btTransform& localAttachmentFrameRef,
|
||||
btTransform& localAttachmentOther,
|
||||
const btVector3& linearMinLimits,
|
||||
const btVector3& linearMaxLimits,
|
||||
const btVector3& angularMinLimits,
|
||||
const btVector3& angularMaxLimits
|
||||
);
|
||||
|
||||
|
||||
@@ -154,7 +154,7 @@ protected:
|
||||
}
|
||||
#endif //NEW_BULLET_VEHICLE_SUPPORT
|
||||
|
||||
TypedConstraint* getConstraintById(int constraintId);
|
||||
btTypedConstraint* getConstraintById(int constraintId);
|
||||
|
||||
virtual PHY_IPhysicsController* rayTest(PHY_IPhysicsController* ignoreClient, float fromX,float fromY,float fromZ, float toX,float toY,float toZ,
|
||||
float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ);
|
||||
@@ -183,7 +183,7 @@ protected:
|
||||
|
||||
void removeCcdPhysicsController(CcdPhysicsController* ctrl);
|
||||
|
||||
BroadphaseInterface* GetBroadphase();
|
||||
btBroadphaseInterface* GetBroadphase();
|
||||
|
||||
|
||||
|
||||
@@ -207,34 +207,34 @@ protected:
|
||||
|
||||
|
||||
|
||||
const PersistentManifold* GetManifold(int index) const;
|
||||
const btPersistentManifold* GetManifold(int index) const;
|
||||
|
||||
std::vector<TypedConstraint*> m_constraints;
|
||||
std::vector<btTypedConstraint*> m_constraints;
|
||||
|
||||
void SyncMotionStates(float timeStep);
|
||||
|
||||
|
||||
class CollisionWorld* GetCollisionWorld()
|
||||
class btCollisionWorld* GetCollisionWorld()
|
||||
{
|
||||
return m_collisionWorld;
|
||||
}
|
||||
|
||||
const class CollisionWorld* GetCollisionWorld() const
|
||||
const class btCollisionWorld* GetCollisionWorld() const
|
||||
{
|
||||
return m_collisionWorld;
|
||||
}
|
||||
|
||||
SimulationIslandManager* GetSimulationIslandManager()
|
||||
btSimulationIslandManager* GetSimulationIslandManager()
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
const SimulationIslandManager* GetSimulationIslandManager() const
|
||||
const btSimulationIslandManager* GetSimulationIslandManager() const
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
class ConstraintSolver* GetConstraintSolver()
|
||||
class btConstraintSolver* GetConstraintSolver()
|
||||
{
|
||||
return m_solver;
|
||||
}
|
||||
@@ -253,9 +253,9 @@ protected:
|
||||
|
||||
std::vector<WrapperVehicle*> m_wrapperVehicles;
|
||||
|
||||
class CollisionWorld* m_collisionWorld;
|
||||
class btCollisionWorld* m_collisionWorld;
|
||||
|
||||
class ConstraintSolver* m_solver;
|
||||
class btConstraintSolver* m_solver;
|
||||
|
||||
bool m_scalingPropagated;
|
||||
|
||||
|
||||
@@ -51,29 +51,29 @@ ParallelIslandDispatcher::ParallelIslandDispatcher ():
|
||||
|
||||
};
|
||||
|
||||
PersistentManifold* ParallelIslandDispatcher::GetNewManifold(void* b0,void* b1)
|
||||
btPersistentManifold* ParallelIslandDispatcher::GetNewManifold(void* b0,void* b1)
|
||||
{
|
||||
gNumManifold2++;
|
||||
|
||||
//ASSERT(gNumManifold < 65535);
|
||||
|
||||
|
||||
CollisionObject* body0 = (CollisionObject*)b0;
|
||||
CollisionObject* body1 = (CollisionObject*)b1;
|
||||
btCollisionObject* body0 = (btCollisionObject*)b0;
|
||||
btCollisionObject* body1 = (btCollisionObject*)b1;
|
||||
|
||||
PersistentManifold* manifold = new PersistentManifold (body0,body1);
|
||||
btPersistentManifold* manifold = new btPersistentManifold (body0,body1);
|
||||
m_manifoldsPtr.push_back(manifold);
|
||||
|
||||
return manifold;
|
||||
}
|
||||
|
||||
void ParallelIslandDispatcher::ClearManifold(PersistentManifold* manifold)
|
||||
void ParallelIslandDispatcher::ClearManifold(btPersistentManifold* manifold)
|
||||
{
|
||||
manifold->ClearManifold();
|
||||
}
|
||||
|
||||
|
||||
void ParallelIslandDispatcher::ReleaseManifold(PersistentManifold* manifold)
|
||||
void ParallelIslandDispatcher::ReleaseManifold(btPersistentManifold* manifold)
|
||||
{
|
||||
|
||||
gNumManifold2--;
|
||||
@@ -82,7 +82,7 @@ void ParallelIslandDispatcher::ReleaseManifold(PersistentManifold* manifold)
|
||||
|
||||
ClearManifold(manifold);
|
||||
|
||||
std::vector<PersistentManifold*>::iterator i =
|
||||
std::vector<btPersistentManifold*>::iterator i =
|
||||
std::find(m_manifoldsPtr.begin(), m_manifoldsPtr.end(), manifold);
|
||||
if (!(i == m_manifoldsPtr.end()))
|
||||
{
|
||||
@@ -99,14 +99,14 @@ void ParallelIslandDispatcher::ReleaseManifold(PersistentManifold* manifold)
|
||||
//
|
||||
// todo: this is random access, it can be walked 'cache friendly'!
|
||||
//
|
||||
void ParallelIslandDispatcher::BuildAndProcessIslands(CollisionObjectArray& collisionObjects, IslandCallback* callback)
|
||||
void ParallelIslandDispatcher::BuildAndProcessIslands(btCollisionObjectArray& collisionObjects, IslandCallback* callback)
|
||||
{
|
||||
int numBodies = collisionObjects.size();
|
||||
|
||||
for (int islandId=0;islandId<numBodies;islandId++)
|
||||
{
|
||||
|
||||
std::vector<PersistentManifold*> islandmanifold;
|
||||
std::vector<btPersistentManifold*> islandmanifold;
|
||||
|
||||
//int numSleeping = 0;
|
||||
|
||||
@@ -115,7 +115,7 @@ void ParallelIslandDispatcher::BuildAndProcessIslands(CollisionObjectArray& coll
|
||||
int i;
|
||||
for (i=0;i<numBodies;i++)
|
||||
{
|
||||
CollisionObject* colObj0 = collisionObjects[i];
|
||||
btCollisionObject* colObj0 = collisionObjects[i];
|
||||
if (colObj0->m_islandTag1 == islandId)
|
||||
{
|
||||
if (colObj0->GetActivationState()== ACTIVE_TAG)
|
||||
@@ -132,12 +132,12 @@ void ParallelIslandDispatcher::BuildAndProcessIslands(CollisionObjectArray& coll
|
||||
|
||||
for (i=0;i<GetNumManifolds();i++)
|
||||
{
|
||||
PersistentManifold* manifold = this->GetManifoldByIndexInternal(i);
|
||||
btPersistentManifold* manifold = this->GetManifoldByIndexInternal(i);
|
||||
|
||||
//filtering for response
|
||||
|
||||
CollisionObject* colObj0 = static_cast<CollisionObject*>(manifold->GetBody0());
|
||||
CollisionObject* colObj1 = static_cast<CollisionObject*>(manifold->GetBody1());
|
||||
btCollisionObject* colObj0 = static_cast<btCollisionObject*>(manifold->GetBody0());
|
||||
btCollisionObject* colObj1 = static_cast<btCollisionObject*>(manifold->GetBody1());
|
||||
{
|
||||
if (((colObj0) && (colObj0)->m_islandTag1 == (islandId)) ||
|
||||
((colObj1) && (colObj1)->m_islandTag1 == (islandId)))
|
||||
@@ -153,7 +153,7 @@ void ParallelIslandDispatcher::BuildAndProcessIslands(CollisionObjectArray& coll
|
||||
int i;
|
||||
for (i=0;i<numBodies;i++)
|
||||
{
|
||||
CollisionObject* colObj0 = collisionObjects[i];
|
||||
btCollisionObject* colObj0 = collisionObjects[i];
|
||||
if (colObj0->m_islandTag1 == islandId)
|
||||
{
|
||||
colObj0->SetActivationState( ISLAND_SLEEPING );
|
||||
@@ -167,7 +167,7 @@ void ParallelIslandDispatcher::BuildAndProcessIslands(CollisionObjectArray& coll
|
||||
int i;
|
||||
for (i=0;i<numBodies;i++)
|
||||
{
|
||||
CollisionObject* colObj0 = collisionObjects[i];
|
||||
btCollisionObject* colObj0 = collisionObjects[i];
|
||||
if (colObj0->m_islandTag1 == islandId)
|
||||
{
|
||||
if ( colObj0->GetActivationState() == ISLAND_SLEEPING)
|
||||
@@ -189,73 +189,73 @@ void ParallelIslandDispatcher::BuildAndProcessIslands(CollisionObjectArray& coll
|
||||
|
||||
|
||||
|
||||
CollisionAlgorithm* ParallelIslandDispatcher::InternalFindAlgorithm(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1)
|
||||
btCollisionAlgorithm* ParallelIslandDispatcher::InternalFindAlgorithm(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
|
||||
{
|
||||
m_count++;
|
||||
CollisionObject* body0 = (CollisionObject*)proxy0.m_clientObject;
|
||||
CollisionObject* body1 = (CollisionObject*)proxy1.m_clientObject;
|
||||
btCollisionObject* body0 = (btCollisionObject*)proxy0.m_clientObject;
|
||||
btCollisionObject* body1 = (btCollisionObject*)proxy1.m_clientObject;
|
||||
|
||||
CollisionAlgorithmConstructionInfo ci;
|
||||
btCollisionAlgorithmConstructionInfo ci;
|
||||
ci.m_dispatcher = this;
|
||||
|
||||
if (body0->m_collisionShape->IsConvex() && body1->m_collisionShape->IsConvex() )
|
||||
{
|
||||
return new ConvexConvexAlgorithm(0,ci,&proxy0,&proxy1);
|
||||
return new btConvexConvexAlgorithm(0,ci,&proxy0,&proxy1);
|
||||
}
|
||||
|
||||
if (body0->m_collisionShape->IsConvex() && body1->m_collisionShape->IsConcave())
|
||||
{
|
||||
return new ConvexConcaveCollisionAlgorithm(ci,&proxy0,&proxy1);
|
||||
return new btConvexConcaveCollisionAlgorithm(ci,&proxy0,&proxy1);
|
||||
}
|
||||
|
||||
if (body1->m_collisionShape->IsConvex() && body0->m_collisionShape->IsConcave())
|
||||
{
|
||||
return new ConvexConcaveCollisionAlgorithm(ci,&proxy1,&proxy0);
|
||||
return new btConvexConcaveCollisionAlgorithm(ci,&proxy1,&proxy0);
|
||||
}
|
||||
|
||||
if (body0->m_collisionShape->IsCompound())
|
||||
{
|
||||
return new CompoundCollisionAlgorithm(ci,&proxy0,&proxy1);
|
||||
return new btCompoundCollisionAlgorithm(ci,&proxy0,&proxy1);
|
||||
} else
|
||||
{
|
||||
if (body1->m_collisionShape->IsCompound())
|
||||
{
|
||||
return new CompoundCollisionAlgorithm(ci,&proxy1,&proxy0);
|
||||
return new btCompoundCollisionAlgorithm(ci,&proxy1,&proxy0);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//failed to find an algorithm
|
||||
return new EmptyAlgorithm(ci);
|
||||
return new btEmptyAlgorithm(ci);
|
||||
|
||||
}
|
||||
|
||||
bool ParallelIslandDispatcher::NeedsResponse(const CollisionObject& colObj0,const CollisionObject& colObj1)
|
||||
bool ParallelIslandDispatcher::NeedsResponse(const btCollisionObject& colObj0,const btCollisionObject& colObj1)
|
||||
{
|
||||
|
||||
|
||||
//here you can do filtering
|
||||
bool hasResponse =
|
||||
(!(colObj0.m_collisionFlags & CollisionObject::noContactResponse)) &&
|
||||
(!(colObj1.m_collisionFlags & CollisionObject::noContactResponse));
|
||||
(!(colObj0.m_collisionFlags & btCollisionObject::noContactResponse)) &&
|
||||
(!(colObj1.m_collisionFlags & btCollisionObject::noContactResponse));
|
||||
hasResponse = hasResponse &&
|
||||
(colObj0.IsActive() || colObj1.IsActive());
|
||||
return hasResponse;
|
||||
}
|
||||
|
||||
bool ParallelIslandDispatcher::NeedsCollision(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1)
|
||||
bool ParallelIslandDispatcher::NeedsCollision(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
|
||||
{
|
||||
|
||||
CollisionObject* body0 = (CollisionObject*)proxy0.m_clientObject;
|
||||
CollisionObject* body1 = (CollisionObject*)proxy1.m_clientObject;
|
||||
btCollisionObject* body0 = (btCollisionObject*)proxy0.m_clientObject;
|
||||
btCollisionObject* body1 = (btCollisionObject*)proxy1.m_clientObject;
|
||||
|
||||
assert(body0);
|
||||
assert(body1);
|
||||
|
||||
bool needsCollision = true;
|
||||
|
||||
if ((body0->m_collisionFlags & CollisionObject::isStatic) &&
|
||||
(body1->m_collisionFlags & CollisionObject::isStatic))
|
||||
if ((body0->m_collisionFlags & btCollisionObject::isStatic) &&
|
||||
(body1->m_collisionFlags & btCollisionObject::isStatic))
|
||||
needsCollision = false;
|
||||
|
||||
if ((!body0->IsActive()) && (!body1->IsActive()))
|
||||
@@ -266,23 +266,23 @@ bool ParallelIslandDispatcher::NeedsCollision(BroadphaseProxy& proxy0,Broadphase
|
||||
}
|
||||
|
||||
///allows the user to get contact point callbacks
|
||||
ManifoldResult* ParallelIslandDispatcher::GetNewManifoldResult(CollisionObject* obj0,CollisionObject* obj1,PersistentManifold* manifold)
|
||||
btManifoldResult* ParallelIslandDispatcher::GetNewManifoldResult(btCollisionObject* obj0,btCollisionObject* obj1,btPersistentManifold* manifold)
|
||||
{
|
||||
|
||||
|
||||
//in-place, this prevents parallel dispatching, but just adding a list would fix that.
|
||||
ManifoldResult* manifoldResult = new (&m_defaultManifoldResult) ManifoldResult(obj0,obj1,manifold);
|
||||
btManifoldResult* manifoldResult = new (&m_defaultManifoldResult) btManifoldResult(obj0,obj1,manifold);
|
||||
return manifoldResult;
|
||||
}
|
||||
|
||||
///allows the user to get contact point callbacks
|
||||
void ParallelIslandDispatcher::ReleaseManifoldResult(ManifoldResult*)
|
||||
void ParallelIslandDispatcher::ReleaseManifoldResult(btManifoldResult*)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
void ParallelIslandDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* pairCache,DispatcherInfo& dispatchInfo)
|
||||
void ParallelIslandDispatcher::DispatchAllCollisionPairs(btOverlappingPairCache* pairCache,btDispatcherInfo& dispatchInfo)
|
||||
{
|
||||
//m_blockedForChanges = true;
|
||||
|
||||
@@ -296,7 +296,7 @@ void ParallelIslandDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* p
|
||||
for (i=0;i<numPairs;i++)
|
||||
{
|
||||
|
||||
BroadphasePair& pair = pairs[i];
|
||||
btBroadphasePair& pair = pairs[i];
|
||||
|
||||
if (dispatcherId>= 0)
|
||||
{
|
||||
@@ -310,7 +310,7 @@ void ParallelIslandDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* p
|
||||
|
||||
if (pair.m_algorithms[dispatcherId])
|
||||
{
|
||||
if (dispatchInfo.m_dispatchFunc == DispatcherInfo::DISPATCH_DISCRETE)
|
||||
if (dispatchInfo.m_dispatchFunc == btDispatcherInfo::DISPATCH_DISCRETE)
|
||||
{
|
||||
pair.m_algorithms[dispatcherId]->ProcessCollision(pair.m_pProxy0,pair.m_pProxy1,dispatchInfo);
|
||||
} else
|
||||
@@ -324,13 +324,13 @@ void ParallelIslandDispatcher::DispatchAllCollisionPairs(OverlappingPairCache* p
|
||||
} else
|
||||
{
|
||||
//non-persistent algorithm dispatcher
|
||||
CollisionAlgorithm* algo = FindAlgorithm(
|
||||
btCollisionAlgorithm* algo = FindAlgorithm(
|
||||
*pair.m_pProxy0,
|
||||
*pair.m_pProxy1);
|
||||
|
||||
if (algo)
|
||||
{
|
||||
if (dispatchInfo.m_dispatchFunc == DispatcherInfo::DISPATCH_DISCRETE)
|
||||
if (dispatchInfo.m_dispatchFunc == btDispatcherInfo::DISPATCH_DISCRETE)
|
||||
{
|
||||
algo->ProcessCollision(pair.m_pProxy0,pair.m_pProxy1,dispatchInfo);
|
||||
} else
|
||||
|
||||
@@ -24,7 +24,7 @@ subject to the following restrictions:
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
|
||||
#include <vector>
|
||||
|
||||
class IDebugDraw;
|
||||
class btIDebugDraw;
|
||||
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
|
||||
@@ -35,28 +35,28 @@ class IDebugDraw;
|
||||
///ParallelIslandDispatcher dispatches entire simulation islands in parallel.
|
||||
///For both collision detection and constraint solving.
|
||||
///This development heads toward multi-core, CELL SPU and GPU approach
|
||||
class ParallelIslandDispatcher : public Dispatcher
|
||||
class ParallelIslandDispatcher : public btDispatcher
|
||||
{
|
||||
|
||||
std::vector<PersistentManifold*> m_manifoldsPtr;
|
||||
std::vector<btPersistentManifold*> m_manifoldsPtr;
|
||||
|
||||
UnionFind m_unionFind;
|
||||
btUnionFind m_unionFind;
|
||||
|
||||
bool m_useIslands;
|
||||
|
||||
ManifoldResult m_defaultManifoldResult;
|
||||
btManifoldResult m_defaultManifoldResult;
|
||||
|
||||
CollisionAlgorithmCreateFunc* m_doubleDispatch[MAX_BROADPHASE_COLLISION_TYPES][MAX_BROADPHASE_COLLISION_TYPES];
|
||||
btCollisionAlgorithmCreateFunc* m_doubleDispatch[MAX_BROADPHASE_COLLISION_TYPES][MAX_BROADPHASE_COLLISION_TYPES];
|
||||
|
||||
public:
|
||||
|
||||
UnionFind& GetUnionFind() { return m_unionFind;}
|
||||
btUnionFind& GetUnionFind() { return m_unionFind;}
|
||||
|
||||
struct IslandCallback
|
||||
{
|
||||
virtual ~IslandCallback() {};
|
||||
|
||||
virtual void ProcessIsland(PersistentManifold** manifolds,int numManifolds) = 0;
|
||||
virtual void ProcessIsland(btPersistentManifold** manifolds,int numManifolds) = 0;
|
||||
};
|
||||
|
||||
|
||||
@@ -65,12 +65,12 @@ public:
|
||||
return m_manifoldsPtr.size();
|
||||
}
|
||||
|
||||
PersistentManifold* GetManifoldByIndexInternal(int index)
|
||||
btPersistentManifold* GetManifoldByIndexInternal(int index)
|
||||
{
|
||||
return m_manifoldsPtr[index];
|
||||
}
|
||||
|
||||
const PersistentManifold* GetManifoldByIndexInternal(int index) const
|
||||
const btPersistentManifold* GetManifoldByIndexInternal(int index) const
|
||||
{
|
||||
return m_manifoldsPtr[index];
|
||||
}
|
||||
@@ -88,37 +88,37 @@ public:
|
||||
ParallelIslandDispatcher ();
|
||||
virtual ~ParallelIslandDispatcher() {};
|
||||
|
||||
virtual PersistentManifold* GetNewManifold(void* b0,void* b1);
|
||||
virtual btPersistentManifold* GetNewManifold(void* b0,void* b1);
|
||||
|
||||
virtual void ReleaseManifold(PersistentManifold* manifold);
|
||||
virtual void ReleaseManifold(btPersistentManifold* manifold);
|
||||
|
||||
|
||||
virtual void BuildAndProcessIslands(CollisionObjectArray& collisionObjects, IslandCallback* callback);
|
||||
virtual void BuildAndProcessIslands(btCollisionObjectArray& collisionObjects, IslandCallback* callback);
|
||||
|
||||
///allows the user to get contact point callbacks
|
||||
virtual ManifoldResult* GetNewManifoldResult(CollisionObject* obj0,CollisionObject* obj1,PersistentManifold* manifold);
|
||||
virtual btManifoldResult* GetNewManifoldResult(btCollisionObject* obj0,btCollisionObject* obj1,btPersistentManifold* manifold);
|
||||
|
||||
///allows the user to get contact point callbacks
|
||||
virtual void ReleaseManifoldResult(ManifoldResult*);
|
||||
virtual void ReleaseManifoldResult(btManifoldResult*);
|
||||
|
||||
virtual void ClearManifold(PersistentManifold* manifold);
|
||||
virtual void ClearManifold(btPersistentManifold* manifold);
|
||||
|
||||
|
||||
CollisionAlgorithm* FindAlgorithm(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1)
|
||||
btCollisionAlgorithm* FindAlgorithm(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
|
||||
{
|
||||
CollisionAlgorithm* algo = InternalFindAlgorithm(proxy0,proxy1);
|
||||
btCollisionAlgorithm* algo = InternalFindAlgorithm(proxy0,proxy1);
|
||||
return algo;
|
||||
}
|
||||
|
||||
CollisionAlgorithm* InternalFindAlgorithm(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1);
|
||||
btCollisionAlgorithm* InternalFindAlgorithm(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1);
|
||||
|
||||
virtual bool NeedsCollision(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1);
|
||||
virtual bool NeedsCollision(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1);
|
||||
|
||||
virtual bool NeedsResponse(const CollisionObject& colObj0,const CollisionObject& colObj1);
|
||||
virtual bool NeedsResponse(const btCollisionObject& colObj0,const btCollisionObject& colObj1);
|
||||
|
||||
virtual int GetUniqueId() { return RIGIDBODY_DISPATCHER;}
|
||||
|
||||
virtual void DispatchAllCollisionPairs(OverlappingPairCache* pairCache,DispatcherInfo& dispatchInfo);
|
||||
virtual void DispatchAllCollisionPairs(btOverlappingPairCache* pairCache,btDispatcherInfo& dispatchInfo);
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -24,7 +24,7 @@ subject to the following restrictions:
|
||||
#include "SimulationIsland.h"
|
||||
|
||||
|
||||
ParallelPhysicsEnvironment::ParallelPhysicsEnvironment(ParallelIslandDispatcher* dispatcher, OverlappingPairCache* pairCache):
|
||||
ParallelPhysicsEnvironment::ParallelPhysicsEnvironment(ParallelIslandDispatcher* dispatcher, btOverlappingPairCache* pairCache):
|
||||
CcdPhysicsEnvironment(dispatcher,pairCache)
|
||||
{
|
||||
|
||||
@@ -41,14 +41,14 @@ ParallelPhysicsEnvironment::~ParallelPhysicsEnvironment()
|
||||
bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
{
|
||||
// Make sure the broadphase / overlapping AABB paircache is up-to-date
|
||||
OverlappingPairCache* scene = m_collisionWorld->GetPairCache();
|
||||
btOverlappingPairCache* scene = m_collisionWorld->GetPairCache();
|
||||
scene->RefreshOverlappingPairs();
|
||||
|
||||
// Find the connected sets that can be simulated in parallel
|
||||
// Using union find
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("IslandUnionFind");
|
||||
btProfiler::beginBlock("IslandUnionFind");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
GetSimulationIslandManager()->UpdateActivationState(GetCollisionWorld(),GetCollisionWorld()->GetDispatcher());
|
||||
@@ -58,10 +58,10 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
int numConstraints = m_constraints.size();
|
||||
for (i=0;i< numConstraints ; i++ )
|
||||
{
|
||||
TypedConstraint* constraint = m_constraints[i];
|
||||
btTypedConstraint* constraint = m_constraints[i];
|
||||
|
||||
const RigidBody* colObj0 = &constraint->GetRigidBodyA();
|
||||
const RigidBody* colObj1 = &constraint->GetRigidBodyB();
|
||||
const btRigidBody* colObj0 = &constraint->GetRigidBodyA();
|
||||
const btRigidBody* colObj1 = &constraint->GetRigidBodyB();
|
||||
|
||||
if (((colObj0) && ((colObj0)->mergesSimulationIslands())) &&
|
||||
((colObj1) && ((colObj1)->mergesSimulationIslands())))
|
||||
@@ -80,7 +80,7 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
GetSimulationIslandManager()->StoreIslandActivationState(GetCollisionWorld());
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("IslandUnionFind");
|
||||
btProfiler::endBlock("IslandUnionFind");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
@@ -88,7 +88,7 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
///build simulation islands
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("BuildIslands");
|
||||
btProfiler::beginBlock("BuildIslands");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
std::vector<SimulationIsland> simulationIslands;
|
||||
@@ -105,7 +105,7 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
}
|
||||
}
|
||||
|
||||
Dispatcher* dispatcher = GetCollisionWorld()->GetDispatcher();
|
||||
btDispatcher* dispatcher = GetCollisionWorld()->GetDispatcher();
|
||||
|
||||
|
||||
//this is a brute force approach, will rethink later about more subtle ways
|
||||
@@ -117,10 +117,10 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
{
|
||||
|
||||
|
||||
BroadphasePair* pair = &scene->GetOverlappingPair(i);
|
||||
btBroadphasePair* pair = &scene->GetOverlappingPair(i);
|
||||
|
||||
CollisionObject* col0 = static_cast<CollisionObject*>(pair->m_pProxy0->m_clientObject);
|
||||
CollisionObject* col1 = static_cast<CollisionObject*>(pair->m_pProxy1->m_clientObject);
|
||||
btCollisionObject* col0 = static_cast<btCollisionObject*>(pair->m_pProxy0->m_clientObject);
|
||||
btCollisionObject* col1 = static_cast<btCollisionObject*>(pair->m_pProxy1->m_clientObject);
|
||||
|
||||
if (col0->m_islandTag1 > col1->m_islandTag1)
|
||||
{
|
||||
@@ -136,7 +136,7 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
//store constraint indices for each island
|
||||
for (unsigned int ui=0;ui<m_constraints.size();ui++)
|
||||
{
|
||||
TypedConstraint& constraint = *m_constraints[ui];
|
||||
btTypedConstraint& constraint = *m_constraints[ui];
|
||||
if (constraint.GetRigidBodyA().m_islandTag1 > constraint.GetRigidBodyB().m_islandTag1)
|
||||
{
|
||||
simulationIslands[constraint.GetRigidBodyA().m_islandTag1].m_constraintIndices.push_back(ui);
|
||||
@@ -151,12 +151,12 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
|
||||
for (i=0;i<dispatcher->GetNumManifolds();i++)
|
||||
{
|
||||
PersistentManifold* manifold = dispatcher->GetManifoldByIndexInternal(i);
|
||||
btPersistentManifold* manifold = dispatcher->GetManifoldByIndexInternal(i);
|
||||
|
||||
//filtering for response
|
||||
|
||||
CollisionObject* colObj0 = static_cast<CollisionObject*>(manifold->GetBody0());
|
||||
CollisionObject* colObj1 = static_cast<CollisionObject*>(manifold->GetBody1());
|
||||
btCollisionObject* colObj0 = static_cast<btCollisionObject*>(manifold->GetBody0());
|
||||
btCollisionObject* colObj1 = static_cast<btCollisionObject*>(manifold->GetBody1());
|
||||
{
|
||||
int islandTag = colObj0->m_islandTag1;
|
||||
if (colObj1->m_islandTag1 > islandTag)
|
||||
@@ -169,15 +169,15 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
}
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("BuildIslands");
|
||||
btProfiler::endBlock("BuildIslands");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("SimulateIsland");
|
||||
btProfiler::beginBlock("SimulateIsland");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
TypedConstraint** constraintBase = 0;
|
||||
btTypedConstraint** constraintBase = 0;
|
||||
if (m_constraints.size())
|
||||
constraintBase = &m_constraints[0];
|
||||
|
||||
@@ -198,7 +198,7 @@ bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("SimulateIsland");
|
||||
btProfiler::endBlock("SimulateIsland");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
return true;
|
||||
|
||||
@@ -29,7 +29,7 @@ class ParallelPhysicsEnvironment : public CcdPhysicsEnvironment
|
||||
|
||||
|
||||
public:
|
||||
ParallelPhysicsEnvironment(ParallelIslandDispatcher* dispatcher=0, OverlappingPairCache* pairCache=0);
|
||||
ParallelPhysicsEnvironment(ParallelIslandDispatcher* dispatcher=0, btOverlappingPairCache* pairCache=0);
|
||||
|
||||
virtual ~ParallelPhysicsEnvironment();
|
||||
|
||||
|
||||
@@ -14,7 +14,7 @@ subject to the following restrictions:
|
||||
*/
|
||||
|
||||
#include "SimulationIsland.h"
|
||||
#include "LinearMath/SimdTransform.h"
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "CcdPhysicsController.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btOverlappingPairCache.h"
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
@@ -22,17 +22,17 @@ subject to the following restrictions:
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btConstraintSolver.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
#include "LinearMath/GenIDebugDraw.h"
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
|
||||
extern float gContactBreakingTreshold;
|
||||
|
||||
bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,TypedConstraint** constraintsBaseAddress,BroadphasePair* overlappingPairBaseAddress, Dispatcher* dispatcher,BroadphaseInterface* broadphase,class ConstraintSolver* solver,float timeStep)
|
||||
bool SimulationIsland::Simulate(btIDebugDraw* debugDrawer,int numSolverIterations,btTypedConstraint** constraintsBaseAddress,btBroadphasePair* overlappingPairBaseAddress, btDispatcher* dispatcher,btBroadphaseInterface* broadphase,class btConstraintSolver* solver,float timeStep)
|
||||
{
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
|
||||
Profiler::beginBlock("predictIntegratedTransform");
|
||||
btProfiler::beginBlock("predictIntegratedTransform");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
{
|
||||
@@ -44,8 +44,8 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
for (k=0;k<GetNumControllers();k++)
|
||||
{
|
||||
CcdPhysicsController* ctrl = m_controllers[k];
|
||||
// SimdTransform predictedTrans;
|
||||
RigidBody* body = ctrl->GetRigidBody();
|
||||
// btTransform predictedTrans;
|
||||
btRigidBody* body = ctrl->GetRigidBody();
|
||||
//todo: only do this when necessary, it's used for contact points
|
||||
body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
|
||||
|
||||
@@ -63,7 +63,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
}
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("predictIntegratedTransform");
|
||||
btProfiler::endBlock("predictIntegratedTransform");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
//BroadphaseInterface* scene = GetBroadphase();
|
||||
@@ -75,20 +75,20 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("DispatchAllCollisionPairs");
|
||||
btProfiler::beginBlock("DispatchAllCollisionPairs");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
// int numsubstep = m_numIterations;
|
||||
|
||||
|
||||
DispatcherInfo dispatchInfo;
|
||||
btDispatcherInfo dispatchInfo;
|
||||
dispatchInfo.m_timeStep = timeStep;
|
||||
dispatchInfo.m_stepCount = 0;
|
||||
dispatchInfo.m_enableSatConvex = false;//m_enableSatCollisionDetection;
|
||||
dispatchInfo.m_debugDraw = debugDrawer;
|
||||
|
||||
std::vector<BroadphasePair> overlappingPairs;
|
||||
std::vector<btBroadphasePair> overlappingPairs;
|
||||
overlappingPairs.resize(this->m_overlappingPairIndices.size());
|
||||
|
||||
//gather overlapping pair info
|
||||
@@ -115,13 +115,13 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("DispatchAllCollisionPairs");
|
||||
btProfiler::endBlock("DispatchAllCollisionPairs");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
//contacts
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("SolveConstraint");
|
||||
btProfiler::beginBlock("SolveConstraint");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
@@ -139,7 +139,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
//point to point constraints
|
||||
for (i=0;i< numConstraints ; i++ )
|
||||
{
|
||||
TypedConstraint* constraint = constraintsBaseAddress[m_constraintIndices[i]];
|
||||
btTypedConstraint* constraint = constraintsBaseAddress[m_constraintIndices[i]];
|
||||
constraint->BuildJacobian();
|
||||
constraint->SolveConstraint( timeStep );
|
||||
|
||||
@@ -149,7 +149,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
}
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("SolveConstraint");
|
||||
btProfiler::endBlock("SolveConstraint");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
/*
|
||||
@@ -162,7 +162,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
for (int i=0;i<numVehicles;i++)
|
||||
{
|
||||
WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
|
||||
RaycastVehicle* vehicle = wrapperVehicle->GetVehicle();
|
||||
btRaycastVehicle* vehicle = wrapperVehicle->GetVehicle();
|
||||
vehicle->UpdateVehicle( timeStep);
|
||||
}
|
||||
#endif //NEW_BULLET_VEHICLE_SUPPORT
|
||||
@@ -170,20 +170,20 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
/*
|
||||
|
||||
Profiler::beginBlock("CallbackTriggers");
|
||||
btProfiler::beginBlock("CallbackTriggers");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
CallbackTriggers();
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("CallbackTriggers");
|
||||
btProfiler::endBlock("CallbackTriggers");
|
||||
|
||||
}
|
||||
*/
|
||||
|
||||
//OverlappingPairCache* scene = GetCollisionWorld()->GetPairCache();
|
||||
|
||||
ContactSolverInfo solverInfo;
|
||||
btContactSolverInfo solverInfo;
|
||||
|
||||
solverInfo.m_friction = 0.9f;
|
||||
solverInfo.m_numIterations = numSolverIterations;
|
||||
@@ -198,7 +198,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("proceedToTransform");
|
||||
btProfiler::beginBlock("proceedToTransform");
|
||||
#endif //USE_QUICKPROF
|
||||
{
|
||||
|
||||
@@ -216,10 +216,10 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
/* if (m_ccdMode == 3)
|
||||
{
|
||||
DispatcherInfo dispatchInfo;
|
||||
btDispatcherInfo dispatchInfo;
|
||||
dispatchInfo.m_timeStep = timeStep;
|
||||
dispatchInfo.m_stepCount = 0;
|
||||
dispatchInfo.m_dispatchFunc = DispatcherInfo::DISPATCH_CONTINUOUS;
|
||||
dispatchInfo.m_dispatchFunc = btDispatcherInfo::DISPATCH_CONTINUOUS;
|
||||
|
||||
// GetCollisionWorld()->GetDispatcher()->DispatchAllCollisionPairs(scene,dispatchInfo);
|
||||
toi = dispatchInfo.m_timeOfImpact;
|
||||
@@ -243,8 +243,8 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
CcdPhysicsController* ctrl = *i;
|
||||
|
||||
SimdTransform predictedTrans;
|
||||
RigidBody* body = ctrl->GetRigidBody();
|
||||
btTransform predictedTrans;
|
||||
btRigidBody* body = ctrl->GetRigidBody();
|
||||
|
||||
if (body->IsActive())
|
||||
{
|
||||
@@ -276,7 +276,7 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
!(i==m_controllers.end()); i++)
|
||||
{
|
||||
CcdPhysicsController* ctrl = (*i);
|
||||
RigidBody* body = ctrl->GetRigidBody();
|
||||
btRigidBody* body = ctrl->GetRigidBody();
|
||||
|
||||
ctrl->UpdateDeactivation(timeStep);
|
||||
|
||||
@@ -313,15 +313,15 @@ bool SimulationIsland::Simulate(IDebugDraw* debugDrawer,int numSolverIterations,
|
||||
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("proceedToTransform");
|
||||
btProfiler::endBlock("proceedToTransform");
|
||||
|
||||
Profiler::beginBlock("SyncMotionStates");
|
||||
btProfiler::beginBlock("SyncMotionStates");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
SyncMotionStates(timeStep);
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("SyncMotionStates");
|
||||
btProfiler::endBlock("SyncMotionStates");
|
||||
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
@@ -363,7 +363,7 @@ void SimulationIsland::SyncMotionStates(float timeStep)
|
||||
|
||||
|
||||
|
||||
void SimulationIsland::UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface* scene,float timeStep)
|
||||
void SimulationIsland::UpdateAabbs(btIDebugDraw* debugDrawer,btBroadphaseInterface* scene,float timeStep)
|
||||
{
|
||||
std::vector<CcdPhysicsController*>::iterator i;
|
||||
|
||||
@@ -375,33 +375,33 @@ void SimulationIsland::UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface*
|
||||
!(i==m_controllers.end()); i++)
|
||||
{
|
||||
CcdPhysicsController* ctrl = (*i);
|
||||
RigidBody* body = ctrl->GetRigidBody();
|
||||
btRigidBody* body = ctrl->GetRigidBody();
|
||||
|
||||
|
||||
SimdPoint3 minAabb,maxAabb;
|
||||
CollisionShape* shapeinterface = ctrl->GetCollisionShape();
|
||||
btPoint3 minAabb,maxAabb;
|
||||
btCollisionShape* shapeinterface = ctrl->GetCollisionShape();
|
||||
|
||||
|
||||
|
||||
shapeinterface->CalculateTemporalAabb(body->getCenterOfMassTransform(),
|
||||
body->getLinearVelocity(),
|
||||
//body->getAngularVelocity(),
|
||||
SimdVector3(0.f,0.f,0.f),//no angular effect for now //body->getAngularVelocity(),
|
||||
btVector3(0.f,0.f,0.f),//no angular effect for now //body->getAngularVelocity(),
|
||||
timeStep,minAabb,maxAabb);
|
||||
|
||||
|
||||
SimdVector3 manifoldExtraExtents(gContactBreakingTreshold,gContactBreakingTreshold,gContactBreakingTreshold);
|
||||
btVector3 manifoldExtraExtents(gContactBreakingTreshold,gContactBreakingTreshold,gContactBreakingTreshold);
|
||||
minAabb -= manifoldExtraExtents;
|
||||
maxAabb += manifoldExtraExtents;
|
||||
|
||||
BroadphaseProxy* bp = body->m_broadphaseHandle;
|
||||
btBroadphaseProxy* bp = body->m_broadphaseHandle;
|
||||
if (bp)
|
||||
{
|
||||
|
||||
SimdVector3 color (1,1,0);
|
||||
btVector3 color (1,1,0);
|
||||
|
||||
/*
|
||||
class IDebugDraw* m_debugDrawer = 0;
|
||||
class btIDebugDraw* m_debugDrawer = 0;
|
||||
if (m_debugDrawer)
|
||||
{
|
||||
//draw aabb
|
||||
@@ -428,7 +428,7 @@ void SimulationIsland::UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface*
|
||||
|
||||
};
|
||||
|
||||
if (m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_DrawAabb)
|
||||
if (m_debugDrawer->GetDebugMode() & btIDebugDraw::DBG_DrawAabb)
|
||||
{
|
||||
DrawAabb(m_debugDrawer,minAabb,maxAabb,color);
|
||||
}
|
||||
|
||||
@@ -17,9 +17,9 @@ subject to the following restrictions:
|
||||
#define SIMULATION_ISLAND_H
|
||||
|
||||
#include <vector>
|
||||
class BroadphaseInterface;
|
||||
class Dispatcher;
|
||||
class IDebugDraw;
|
||||
class btBroadphaseInterface;
|
||||
class btDispatcher;
|
||||
class btIDebugDraw;
|
||||
|
||||
///SimulationIsland groups all computations and data (for collision detection and dynamics) that can execute in parallel with other SimulationIsland's
|
||||
///The ParallelPhysicsEnvironment and ParallelIslandDispatcher will dispatch SimulationIsland's
|
||||
@@ -30,12 +30,12 @@ class SimulationIsland
|
||||
|
||||
public:
|
||||
std::vector<class CcdPhysicsController*> m_controllers;
|
||||
std::vector<class PersistentManifold*> m_manifolds;
|
||||
std::vector<class btPersistentManifold*> m_manifolds;
|
||||
|
||||
std::vector<int> m_overlappingPairIndices;
|
||||
std::vector<int> m_constraintIndices;
|
||||
|
||||
bool Simulate(IDebugDraw* debugDrawer,int numSolverIterations,class TypedConstraint** constraintsBaseAddress,struct BroadphasePair* overlappingPairBaseAddress, Dispatcher* dispatcher,BroadphaseInterface* broadphase, class ConstraintSolver* solver, float timeStep);
|
||||
bool Simulate(btIDebugDraw* debugDrawer,int numSolverIterations,class btTypedConstraint** constraintsBaseAddress,struct btBroadphasePair* overlappingPairBaseAddress, btDispatcher* dispatcher,btBroadphaseInterface* broadphase, class btConstraintSolver* solver, float timeStep);
|
||||
|
||||
|
||||
int GetNumControllers()
|
||||
@@ -47,7 +47,7 @@ class SimulationIsland
|
||||
|
||||
|
||||
void SyncMotionStates(float timeStep);
|
||||
void UpdateAabbs(IDebugDraw* debugDrawer,BroadphaseInterface* broadphase,float timeStep);
|
||||
void UpdateAabbs(btIDebugDraw* debugDrawer,btBroadphaseInterface* broadphase,float timeStep);
|
||||
};
|
||||
|
||||
#endif //SIMULATION_ISLAND_H
|
||||
|
||||
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
#define PHY_PROPSH
|
||||
|
||||
|
||||
class CollisionShape;
|
||||
class btCollisionShape;
|
||||
|
||||
// Properties of dynamic objects
|
||||
struct PHY_ShapeProps {
|
||||
@@ -29,7 +29,7 @@ struct PHY_ShapeProps {
|
||||
bool m_do_anisotropic; // Should I do anisotropic friction?
|
||||
bool m_do_fh; // Should the object have a linear Fh spring?
|
||||
bool m_do_rot_fh; // Should the object have an angular Fh spring?
|
||||
CollisionShape* m_shape;
|
||||
btCollisionShape* m_shape;
|
||||
};
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user