Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <blender@erwincoumans.com>2006-11-21 03:53:40 +0300
committerErwin Coumans <blender@erwincoumans.com>2006-11-21 03:53:40 +0300
commit46234f90cee9b3967cb6361661ce47b455cbaa57 (patch)
tree8f32252f55c29694c1fa619d00a67ea4b4941099 /source/gameengine/Physics
parent4bbbabd04957d6564d43b076e1e144f0bb4da439 (diff)
Removed old Blender/extern/bullet, and upgraded game engine to use Bullet 2.x
All platforms/build systems: either upgrade to use extern/bullet2, or disable the game engine until the build is fixed.
Diffstat (limited to 'source/gameengine/Physics')
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsController.cpp222
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsController.h60
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp1395
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h91
-rw-r--r--source/gameengine/Physics/common/PHY_IVehicle.h1
5 files changed, 527 insertions, 1242 deletions
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp b/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp
index 83bddc8ee1e..e542c336559 100644
--- a/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp
+++ b/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp
@@ -14,32 +14,28 @@ subject to the following restrictions:
*/
#include "CcdPhysicsController.h"
+#include "btBulletDynamicsCommon.h"
-#include "Dynamics/RigidBody.h"
#include "PHY_IMotionState.h"
-#include "BroadphaseCollision/BroadphaseProxy.h"
-#include "BroadphaseCollision/BroadphaseInterface.h"
-#include "CollisionShapes/ConvexShape.h"
#include "CcdPhysicsEnvironment.h"
-#include "SimdTransformUtil.h"
-#include "CollisionShapes/SphereShape.h"
-#include "CollisionShapes/ConeShape.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;
-bool gDisableDeactivation = false;
+//float gDeactivationTime = 2.f;
+//bool gDisableDeactivation = false;
+extern float gDeactivationTime;
+extern bool gDisableDeactivation;
+
float gLinearSleepingTreshold = 0.8f;
float gAngularSleepingTreshold = 1.0f;
-#include "Dynamics/MassProps.h"
-SimdVector3 startVel(0,0,0);//-10000);
+btVector3 startVel(0,0,0);//-10000);
CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
:m_cci(ci)
{
@@ -47,7 +43,7 @@ CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
m_newClientInfo = 0;
m_MotionState = ci.m_MotionState;
-
+ m_bulletMotionState = 0;
CreateRigidbody();
@@ -61,51 +57,85 @@ 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;
}
+class BlenderBulletMotionState : public btMotionState
+{
+ PHY_IMotionState* m_blenderMotionState;
+
+public:
+
+ BlenderBulletMotionState(PHY_IMotionState* bms)
+ :m_blenderMotionState(bms)
+ {
+
+ }
+
+ virtual void getWorldTransform(btTransform& worldTrans ) const
+ {
+ float pos[3];
+ float quatOrn[4];
+
+ m_blenderMotionState->getWorldPosition(pos[0],pos[1],pos[2]);
+ m_blenderMotionState->getWorldOrientation(quatOrn[0],quatOrn[1],quatOrn[2],quatOrn[3]);
+ worldTrans.setOrigin(btVector3(pos[0],pos[1],pos[2]));
+ worldTrans.setBasis(btMatrix3x3(btQuaternion(quatOrn[0],quatOrn[1],quatOrn[2],quatOrn[3])));
+ }
+
+ virtual void setWorldTransform(const btTransform& worldTrans)
+ {
+ m_blenderMotionState->setWorldPosition(worldTrans.getOrigin().getX(),worldTrans.getOrigin().getY(),worldTrans.getOrigin().getZ());
+ btQuaternion rotQuat = worldTrans.getRotation();
+ m_blenderMotionState->setWorldOrientation(rotQuat[0],rotQuat[1],rotQuat[2],rotQuat[3]);
+
+ }
+
+};
+
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);
+ m_bulletMotionState = new BlenderBulletMotionState(m_cci.m_MotionState);
- m_body = new RigidBody(mp,0,0,m_cci.m_friction,m_cci.m_restitution);
- m_body->m_collisionShape = m_cci.m_collisionShape;
+ m_body = new btRigidBody(m_cci.m_mass,m_bulletMotionState,m_cci.m_collisionShape,m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor,m_cci.m_friction,m_cci.m_restitution);
//
// init the rigidbody properly
//
- m_body->setMassProps(m_cci.m_mass, m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
//setMassProps this also sets collisionFlags
- m_body->m_collisionFlags = m_cci.m_collisionFlags;
+ //convert collision flags!
+// m_body->m_collisionFlags = m_cci.m_collisionFlags;
m_body->setGravity( m_cci.m_gravity);
m_body->setDamping(m_cci.m_linearDamping, m_cci.m_angularDamping);
- m_body->setCenterOfMassTransform( trans );
-
}
CcdPhysicsController::~CcdPhysicsController()
{
//will be reference counted, due to sharing
- m_cci.m_physicsEnv->removeCcdPhysicsController(this);
+ if (m_cci.m_physicsEnv)
+ m_cci.m_physicsEnv->removeCcdPhysicsController(this);
+
delete m_MotionState;
+ if (m_bulletMotionState)
+ delete m_bulletMotionState;
delete m_body;
}
@@ -116,29 +146,29 @@ bool CcdPhysicsController::SynchronizeMotionStates(float time)
{
//sync non-static to motionstate, and static from motionstate (todo: add kinematic etc.)
- if (!m_body->IsStatic())
+ if (!m_body->isStaticObject())
{
- 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...
@@ -147,7 +177,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;
@@ -217,8 +247,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)
{
@@ -237,15 +267,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)));
@@ -255,17 +285,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];
@@ -274,9 +304,9 @@ void CcdPhysicsController::getOrientation(float &quatImag0,float &quatImag1,flo
void CcdPhysicsController::setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal)
{
m_body->activate();
-
- SimdTransform xform = m_body->getCenterOfMassTransform();
- xform.setRotation(SimdQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
+ m_MotionState->setWorldOrientation(quatImag0,quatImag1,quatImag2,quatReal);
+ btTransform xform = m_body->getCenterOfMassTransform();
+ xform.setRotation(btQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
m_body->setCenterOfMassTransform(xform);
}
@@ -284,9 +314,9 @@ void CcdPhysicsController::setOrientation(float quatImag0,float quatImag1,float
void CcdPhysicsController::setPosition(float posX,float posY,float posZ)
{
m_body->activate();
-
- SimdTransform xform = m_body->getCenterOfMassTransform();
- xform.setOrigin(SimdVector3(posX,posY,posZ));
+ m_MotionState->setWorldPosition(posX,posY,posZ);
+ btTransform xform = m_body->getCenterOfMassTransform();
+ xform.setOrigin(btVector3(posX,posY,posZ));
m_body->setCenterOfMassTransform(xform);
}
@@ -296,7 +326,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();
@@ -304,16 +334,16 @@ 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())
+ if (m_body && m_body->getCollisionShape())
{
- m_body->GetCollisionShape()->setLocalScaling(m_cci.m_scaling);
- m_body->GetCollisionShape()->CalculateLocalInertia(m_cci.m_mass, m_cci.m_localInertiaTensor);
+ m_body->getCollisionShape()->setLocalScaling(m_cci.m_scaling);
+ m_body->getCollisionShape()->calculateLocalInertia(m_cci.m_mass, m_cci.m_localInertiaTensor);
m_body->setMassProps(m_cci.m_mass, m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
}
}
@@ -322,8 +352,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;
@@ -333,8 +363,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;
@@ -343,14 +373,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;
@@ -363,14 +393,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;
@@ -380,13 +410,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();
@@ -400,7 +430,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();
@@ -409,7 +439,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();
@@ -417,9 +447,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();
@@ -434,7 +464,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();
@@ -454,62 +484,36 @@ void CcdPhysicsController::setNewClientInfo(void* clientinfo)
void CcdPhysicsController::UpdateDeactivation(float timeStep)
{
- if ( (m_body->GetActivationState() == ISLAND_SLEEPING) || (m_body->GetActivationState() == DISABLE_DEACTIVATION))
- return;
-
- if ((m_body->getLinearVelocity().length2() < gLinearSleepingTreshold*gLinearSleepingTreshold) &&
- (m_body->getAngularVelocity().length2() < gAngularSleepingTreshold*gAngularSleepingTreshold))
- {
- m_body->m_deactivationTime += timeStep;
- } else
- {
- m_body->m_deactivationTime=0.f;
- m_body->SetActivationState(0);
- }
-
+ m_body->updateDeactivation( timeStep);
}
bool CcdPhysicsController::wantsSleeping()
{
- if (m_body->GetActivationState() == DISABLE_DEACTIVATION)
- return false;
-
- //disable deactivation
- if (gDisableDeactivation || (gDeactivationTime == 0.f))
- return false;
-
- if ( (m_body->GetActivationState() == ISLAND_SLEEPING) || (m_body->GetActivationState() == WANTS_DEACTIVATION))
- return true;
-
- if (m_body->m_deactivationTime> gDeactivationTime)
- {
- return true;
- }
- return false;
+ return m_body->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;
if (cinfo.m_collisionShape)
{
- switch (cinfo.m_collisionShape->GetShapeType())
+ 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;
}
@@ -568,13 +572,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 );
}
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsController.h b/source/gameengine/Physics/Bullet/CcdPhysicsController.h
index 632d5d776d2..11fef56401f 100644
--- a/source/gameengine/Physics/Bullet/CcdPhysicsController.h
+++ b/source/gameengine/Physics/Bullet/CcdPhysicsController.h
@@ -21,23 +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 "SimdVector3.h"
-#include "SimdScalar.h"
-#include "SimdMatrix3x3.h"
-#include "SimdTransform.h"
-#include "Dynamics/RigidBody.h"
+#include "btBulletDynamicsCommon.h"
#include "PHY_IMotionState.h"
-#include "BroadphaseCollision/BroadphaseProxy.h" //for CollisionShape access
-class CollisionShape;
-
extern float gDeactivationTime;
extern float gLinearSleepingTreshold;
extern float gAngularSleepingTreshold;
extern bool gDisableDeactivation;
class CcdPhysicsEnvironment;
-
+class btMotionState;
@@ -46,7 +39,7 @@ struct CcdConstructionInfo
///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,
@@ -74,46 +67,47 @@ 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
float m_inertiaFactor;//tweak the inertia (hooked up to Blender 'formfactor'
};
-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;
-
+ btMotionState* m_bulletMotionState;
+
void* m_newClientInfo;
CcdConstructionInfo m_cci;//needed for replication
- void GetWorldOrientation(SimdMatrix3x3& mat);
+ void GetWorldOrientation(btMatrix3x3& mat);
void CreateRigidbody();
@@ -127,10 +121,10 @@ class CcdPhysicsController : public PHY_IPhysicsController
virtual ~CcdPhysicsController();
- RigidBody* GetRigidBody() { return m_body;}
+ btRigidBody* GetRigidBody() { return m_body;}
- CollisionShape* GetCollisionShape() {
- return m_body->GetCollisionShape();
+ btCollisionShape* GetCollisionShape() {
+ return m_body->getCollisionShape();
}
////////////////////////////////////
// PHY_IPhysicsController interface
@@ -206,9 +200,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 +221,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 +239,8 @@ class DefaultMotionState : public PHY_IMotionState
virtual void calculateWorldTransformations();
- SimdTransform m_worldTransform;
- SimdVector3 m_localScaling;
+ btTransform m_worldTransform;
+ btVector3 m_localScaling;
};
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp
index 813462fdf5e..9533adfa3d5 100644
--- a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp
+++ b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp
@@ -20,74 +20,36 @@ subject to the following restrictions:
#include "CcdPhysicsController.h"
#include <algorithm>
-#include "SimdTransform.h"
-#include "Dynamics/RigidBody.h"
-#include "BroadphaseCollision/BroadphaseInterface.h"
-#include "BroadphaseCollision/SimpleBroadphase.h"
-#include "BroadphaseCollision/AxisSweep3.h"
-
-#include "CollisionDispatch/CollisionWorld.h"
-
-#include "CollisionShapes/ConvexShape.h"
-#include "CollisionShapes/ConeShape.h"
-#include "CollisionDispatch/SimulationIslandManager.h"
-
-#include "BroadphaseCollision/Dispatcher.h"
-#include "NarrowPhaseCollision/PersistentManifold.h"
-#include "CollisionShapes/TriangleMeshShape.h"
-#include "ConstraintSolver/SequentialImpulseConstraintSolver.h"
-
+#include "btBulletDynamicsCommon.h"
+#include "LinearMath/btIDebugDraw.h"
+#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
//profiling/timings
-#include "quickprof.h"
-
+#include "LinearMath/btQuickprof.h"
-#include "IDebugDraw.h"
-#include "NarrowPhaseCollision/VoronoiSimplexSolver.h"
-#include "NarrowPhaseCollision/SubSimplexConvexCast.h"
-#include "NarrowPhaseCollision/GjkConvexCast.h"
-#include "NarrowPhaseCollision/ContinuousConvexCollision.h"
-
-
-#include "CollisionDispatch/CollisionDispatcher.h"
#include "PHY_IMotionState.h"
-#include "CollisionDispatch/EmptyCollisionAlgorithm.h"
-
-
-
-#include "CollisionShapes/SphereShape.h"
bool useIslands = true;
#ifdef NEW_BULLET_VEHICLE_SUPPORT
-#include "Vehicle/RaycastVehicle.h"
-#include "Vehicle/VehicleRaycaster.h"
-
-#include "Vehicle/WheelInfo.h"
+#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
+#include "BulletDynamics/Vehicle/btVehicleRaycaster.h"
+#include "BulletDynamics/Vehicle/btWheelInfo.h"
#include "PHY_IVehicle.h"
-RaycastVehicle::VehicleTuning gTuning;
+btRaycastVehicle::btVehicleTuning gTuning;
#endif //NEW_BULLET_VEHICLE_SUPPORT
-#include "AabbUtil2.h"
-
-#include "ConstraintSolver/ConstraintSolver.h"
-#include "ConstraintSolver/Point2PointConstraint.h"
-#include "ConstraintSolver/HingeConstraint.h"
-#include "ConstraintSolver/Generic6DofConstraint.h"
-
+#include "LinearMath/btAabbUtil2.h"
-//#include "BroadphaseCollision/QueryDispatcher.h"
-//#include "BroadphaseCollision/QueryBox.h"
-//todo: change this to allow dynamic registration of types!
#ifdef WIN32
void DrawRasterizerLine(const float* from,const float* to,int color);
#endif
-#include "ConstraintSolver/ContactConstraint.h"
+#include "BulletDynamics/ConstraintSolver/btContactConstraint.h"
#include <stdio.h>
@@ -96,18 +58,18 @@ void DrawRasterizerLine(const float* from,const float* to,int color);
class WrapperVehicle : public PHY_IVehicle
{
- RaycastVehicle* m_vehicle;
+ btRaycastVehicle* m_vehicle;
PHY_IPhysicsController* m_chassis;
public:
- WrapperVehicle(RaycastVehicle* vehicle,PHY_IPhysicsController* chassis)
+ WrapperVehicle(btRaycastVehicle* vehicle,PHY_IPhysicsController* chassis)
:m_vehicle(vehicle),
m_chassis(chassis)
{
}
- RaycastVehicle* GetVehicle()
+ btRaycastVehicle* GetVehicle()
{
return m_vehicle;
}
@@ -127,12 +89,12 @@ public:
bool hasSteering
)
{
- SimdVector3 connectionPointCS0(connectionPoint[0],connectionPoint[1],connectionPoint[2]);
- SimdVector3 wheelDirectionCS0(downDirection[0],downDirection[1],downDirection[2]);
- SimdVector3 wheelAxle(axleDirection[0],axleDirection[1],axleDirection[2]);
+ btVector3 connectionPointCS0(connectionPoint[0],connectionPoint[1],connectionPoint[2]);
+ btVector3 wheelDirectionCS0(downDirection[0],downDirection[1],downDirection[2]);
+ btVector3 wheelAxle(axleDirection[0],axleDirection[1],axleDirection[2]);
- WheelInfo& info = m_vehicle->AddWheel(connectionPointCS0,wheelDirectionCS0,wheelAxle,
+ btWheelInfo& info = m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxle,
suspensionRestLength,wheelRadius,gTuning,hasSteering);
info.m_clientInfo = motionState;
@@ -144,12 +106,12 @@ public:
int i;
for (i=0;i<numWheels;i++)
{
- WheelInfo& info = m_vehicle->GetWheelInfo(i);
+ btWheelInfo& info = m_vehicle->getWheelInfo(i);
PHY_IMotionState* motionState = (PHY_IMotionState*)info.m_clientInfo ;
- m_vehicle->UpdateWheelTransform(i);
- SimdTransform trans = m_vehicle->GetWheelTransformWS(i);
- SimdQuaternion orn = trans.getRotation();
- const SimdVector3& pos = trans.getOrigin();
+ m_vehicle->updateWheelTransform(i);
+ btTransform trans = m_vehicle->getWheelTransformWS(i);
+ btQuaternion orn = trans.getRotation();
+ const btVector3& pos = trans.getOrigin();
motionState->setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]);
motionState->setWorldPosition(pos.x(),pos.y(),pos.z());
@@ -158,21 +120,21 @@ public:
virtual int GetNumWheels() const
{
- return m_vehicle->GetNumWheels();
+ return m_vehicle->getNumWheels();
}
virtual void GetWheelPosition(int wheelIndex,float& posX,float& posY,float& posZ) const
{
- SimdTransform trans = m_vehicle->GetWheelTransformWS(wheelIndex);
+ btTransform trans = m_vehicle->getWheelTransformWS(wheelIndex);
posX = trans.getOrigin().x();
posY = trans.getOrigin().y();
posZ = trans.getOrigin().z();
}
virtual void GetWheelOrientationQuaternion(int wheelIndex,float& quatX,float& quatY,float& quatZ,float& quatW) const
{
- SimdTransform trans = m_vehicle->GetWheelTransformWS(wheelIndex);
- SimdQuaternion quat = trans.getRotation();
- SimdMatrix3x3 orn2(quat);
+ btTransform trans = m_vehicle->getWheelTransformWS(wheelIndex);
+ btQuaternion quat = trans.getRotation();
+ btMatrix3x3 orn2(quat);
quatX = trans.getRotation().x();
quatY = trans.getRotation().y();
@@ -189,9 +151,9 @@ public:
{
float rotation = 0.f;
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
rotation = info.m_rotation;
}
return rotation;
@@ -202,38 +164,38 @@ public:
virtual int GetUserConstraintId() const
{
- return m_vehicle->GetUserConstraintId();
+ return m_vehicle->getUserConstraintId();
}
virtual int GetUserConstraintType() const
{
- return m_vehicle->GetUserConstraintType();
+ return m_vehicle->getUserConstraintType();
}
virtual void SetSteeringValue(float steering,int wheelIndex)
{
- m_vehicle->SetSteeringValue(steering,wheelIndex);
+ m_vehicle->setSteeringValue(steering,wheelIndex);
}
virtual void ApplyEngineForce(float force,int wheelIndex)
{
- m_vehicle->ApplyEngineForce(force,wheelIndex);
+ m_vehicle->applyEngineForce(force,wheelIndex);
}
virtual void ApplyBraking(float braking,int wheelIndex)
{
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
info.m_brake = braking;
}
}
virtual void SetWheelFriction(float friction,int wheelIndex)
{
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
info.m_frictionSlip = friction;
}
@@ -241,9 +203,9 @@ public:
virtual void SetSuspensionStiffness(float suspensionStiffness,int wheelIndex)
{
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
info.m_suspensionStiffness = suspensionStiffness;
}
@@ -251,18 +213,18 @@ public:
virtual void SetSuspensionDamping(float suspensionDamping,int wheelIndex)
{
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
info.m_wheelsDampingRelaxation = suspensionDamping;
}
}
virtual void SetSuspensionCompression(float suspensionCompression,int wheelIndex)
{
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
info.m_wheelsDampingCompression = suspensionCompression;
}
}
@@ -271,13 +233,18 @@ public:
virtual void SetRollInfluence(float rollInfluence,int wheelIndex)
{
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->GetNumWheels()))
+ if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
{
- WheelInfo& info = m_vehicle->GetWheelInfo(wheelIndex);
+ btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
info.m_rollInfluence = rollInfluence;
}
}
+ virtual void SetCoordinateSystem(int rightIndex,int upIndex,int forwardIndex)
+ {
+ m_vehicle->setCoordinateSystem(rightIndex,upIndex,forwardIndex);
+ }
+
};
@@ -285,30 +252,30 @@ public:
-static void DrawAabb(IDebugDraw* debugDrawer,const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)
+static void DrawAabb(btIDebugDraw* debugDrawer,const btVector3& from,const btVector3& to,const btVector3& color)
{
- SimdVector3 halfExtents = (to-from)* 0.5f;
- SimdVector3 center = (to+from) *0.5f;
+ btVector3 halfExtents = (to-from)* 0.5f;
+ btVector3 center = (to+from) *0.5f;
int i,j;
- SimdVector3 edgecoord(1.f,1.f,1.f),pa,pb;
+ btVector3 edgecoord(1.f,1.f,1.f),pa,pb;
for (i=0;i<4;i++)
{
for (j=0;j<3;j++)
{
- pa = SimdVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
+ pa = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
edgecoord[2]*halfExtents[2]);
pa+=center;
int othercoord = j%3;
edgecoord[othercoord]*=-1.f;
- pb = SimdVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
+ pb = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
edgecoord[2]*halfExtents[2]);
pb+=center;
- debugDrawer->DrawLine(pa,pb,color);
+ debugDrawer->drawLine(pa,pb,color);
}
- edgecoord = SimdVector3(-1.f,-1.f,-1.f);
+ edgecoord = btVector3(-1.f,-1.f,-1.f);
if (i<3)
edgecoord[i]*=-1.f;
}
@@ -321,7 +288,7 @@ static void DrawAabb(IDebugDraw* debugDrawer,const SimdVector3& from,const SimdV
-CcdPhysicsEnvironment::CcdPhysicsEnvironment(Dispatcher* dispatcher,OverlappingPairCache* pairCache)
+CcdPhysicsEnvironment::CcdPhysicsEnvironment(btDispatcher* dispatcher,btOverlappingPairCache* pairCache)
:m_scalingPropagated(false),
m_numIterations(10),
m_numTimeSubSteps(1),
@@ -335,71 +302,68 @@ m_enableSatCollisionDetection(false)
{
m_triggerCallbacks[i] = 0;
}
-
if (!dispatcher)
- dispatcher = new CollisionDispatcher();
+ dispatcher = new btCollisionDispatcher();
if(!pairCache)
{
//todo: calculate/let user specify this world sizes
- SimdVector3 worldMin(-10000,-10000,-10000);
- SimdVector3 worldMax(10000,10000,10000);
+ btVector3 worldMin(-10000,-10000,-10000);
+ btVector3 worldMax(10000,10000,10000);
- pairCache = new AxisSweep3(worldMin,worldMax);
+ pairCache = new btAxisSweep3(worldMin,worldMax);
- //broadphase = new SimpleBroadphase();
+ //broadphase = new btSimpleBroadphase();
}
setSolverType(1);//issues with quickstep and memory allocations
- m_collisionWorld = new CollisionWorld(dispatcher,pairCache);
-
+ m_dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,pairCache);
m_debugDrawer = 0;
- m_gravity = SimdVector3(0.f,-10.f,0.f);
-
- m_islandManager = new SimulationIslandManager();
+ m_gravity = btVector3(0.f,-10.f,0.f);
+ m_dynamicsWorld->setGravity(m_gravity);
}
void CcdPhysicsEnvironment::addCcdPhysicsController(CcdPhysicsController* ctrl)
{
- RigidBody* body = ctrl->GetRigidBody();
+ btRigidBody* body = ctrl->GetRigidBody();
//this m_userPointer is just used for triggers, see CallbackTriggers
- body->m_userPointer = ctrl;
+ body->setUserPointer(ctrl);
body->setGravity( m_gravity );
m_controllers.push_back(ctrl);
- m_collisionWorld->AddCollisionObject(body,ctrl->GetCollisionFilterGroup(),ctrl->GetCollisionFilterMask());
+ m_dynamicsWorld->addRigidBody(body);
+ //CollisionObject(body,ctrl->GetCollisionFilterGroup(),ctrl->GetCollisionFilterMask());
- assert(body->m_broadphaseHandle);
+ assert(body->getBroadphaseHandle());
- BroadphaseInterface* scene = GetBroadphase();
+ btBroadphaseInterface* scene = getBroadphase();
- CollisionShape* shapeinterface = ctrl->GetCollisionShape();
+ btCollisionShape* shapeinterface = ctrl->GetCollisionShape();
assert(shapeinterface);
- const SimdTransform& t = ctrl->GetRigidBody()->getCenterOfMassTransform();
+ const btTransform& t = ctrl->GetRigidBody()->getCenterOfMassTransform();
- body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
- SimdPoint3 minAabb,maxAabb;
+ btPoint3 minAabb,maxAabb;
- shapeinterface->GetAabb(t,minAabb,maxAabb);
+ shapeinterface->getAabb(t,minAabb,maxAabb);
float timeStep = 0.02f;
//extent it with the motion
- SimdVector3 linMotion = body->getLinearVelocity()*timeStep;
+ btVector3 linMotion = body->getLinearVelocity()*timeStep;
float maxAabbx = maxAabb.getX();
float maxAabby = maxAabb.getY();
@@ -422,8 +386,8 @@ void CcdPhysicsEnvironment::addCcdPhysicsController(CcdPhysicsController* ctrl)
minAabbz += linMotion.z();
- minAabb = SimdVector3(minAabbx,minAabby,minAabbz);
- maxAabb = SimdVector3(maxAabbx,maxAabby,maxAabbz);
+ minAabb = btVector3(minAabbx,minAabby,minAabbz);
+ maxAabb = btVector3(maxAabbx,maxAabby,maxAabbz);
@@ -435,42 +399,9 @@ void CcdPhysicsEnvironment::removeCcdPhysicsController(CcdPhysicsController* ctr
//also remove constraint
- {
- std::vector<TypedConstraint*>::iterator i;
-
- for (i=m_constraints.begin();
- !(i==m_constraints.end()); i++)
- {
- TypedConstraint* constraint = (*i);
- if ((&constraint->GetRigidBodyA() == ctrl->GetRigidBody() ||
- (&constraint->GetRigidBodyB() == ctrl->GetRigidBody())))
- {
- removeConstraint(constraint->GetUserConstraintId());
- //only 1 constraint per constroller
- break;
- }
- }
- }
-
- {
- std::vector<TypedConstraint*>::iterator i;
-
- for (i=m_constraints.begin();
- !(i==m_constraints.end()); i++)
- {
- TypedConstraint* constraint = (*i);
- if ((&constraint->GetRigidBodyA() == ctrl->GetRigidBody() ||
- (&constraint->GetRigidBodyB() == ctrl->GetRigidBody())))
- {
- removeConstraint(constraint->GetUserConstraintId());
- //only 1 constraint per constroller
- break;
- }
- }
- }
-
+
- m_collisionWorld->RemoveCollisionObject(ctrl->GetRigidBody());
+ m_dynamicsWorld->removeRigidBody(ctrl->GetRigidBody());
{
@@ -506,482 +437,24 @@ void CcdPhysicsEnvironment::beginFrame()
bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
{
- //don't simulate without timesubsteps
- if (m_numTimeSubSteps<1)
- return true;
-
- //printf("proceedDeltaTime\n");
-
-
-#ifdef USE_QUICKPROF
- //toggle Profiler
- if ( m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_ProfileTimings)
- {
- if (!m_profileTimings)
- {
- m_profileTimings = 1;
- // To disable profiling, simply comment out the following line.
- static int counter = 0;
-
- char filename[128];
- sprintf(filename,"quickprof_bullet_timings%i.csv",counter++);
- Profiler::init(filename, Profiler::BLOCK_CYCLE_SECONDS);//BLOCK_TOTAL_MICROSECONDS
-
- }
- } else
- {
- if (m_profileTimings)
- {
- m_profileTimings = 0;
- Profiler::destroy();
- }
- }
-#endif //USE_QUICKPROF
-
-
-
- if (!SimdFuzzyZero(timeStep))
- {
-
- {
- //do the kinematic calculation here, over the full timestep
- std::vector<CcdPhysicsController*>::iterator i;
- for (i=m_controllers.begin();
- !(i==m_controllers.end()); i++)
- {
-
- CcdPhysicsController* ctrl = *i;
-
- SimdTransform predictedTrans;
- RigidBody* body = ctrl->GetRigidBody();
- if (body->GetActivationState() != ISLAND_SLEEPING)
- {
-
- if (body->IsStatic())
- {
- //to calculate velocities next frame
- body->saveKinematicState(timeStep);
- }
- }
- }
- }
-
- int i;
- float subTimeStep = timeStep / float(m_numTimeSubSteps);
-
- for (i=0;i<this->m_numTimeSubSteps;i++)
- {
- proceedDeltaTimeOneStep(subTimeStep);
- }
- } else
+ int numCtrl = GetNumControllers();
+ for (int i=0;i<numCtrl;i++)
{
- //todo: interpolate
- }
-
- return true;
-}
-
-
-
-
-
-
-
-
-
-
-
-
-
-/// Perform an integration step of duration 'timeStep'.
-bool CcdPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
-{
-
-
- //printf("CcdPhysicsEnvironment::proceedDeltaTime\n");
-
- if (SimdFuzzyZero(timeStep))
- return true;
-
- if (m_debugDrawer)
- {
- gDisableDeactivation = (m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_NoDeactivation);
- }
-
-
-#ifdef USE_QUICKPROF
- Profiler::beginBlock("SyncMotionStates");
-#endif //USE_QUICKPROF
-
-
- //this is needed because scaling is not known in advance, and scaling has to propagate to the shape
- if (!m_scalingPropagated)
- {
- SyncMotionStates(timeStep);
- m_scalingPropagated = true;
- }
-
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("SyncMotionStates");
-
- Profiler::beginBlock("predictIntegratedTransform");
-#endif //USE_QUICKPROF
-
- {
- // std::vector<CcdPhysicsController*>::iterator i;
-
-
-
- int k;
- for (k=0;k<GetNumControllers();k++)
- {
- CcdPhysicsController* ctrl = m_controllers[k];
- // SimdTransform predictedTrans;
- RigidBody* body = ctrl->GetRigidBody();
-
- body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
-
- if (body->IsActive())
- {
- if (!body->IsStatic())
- {
- body->applyForces( timeStep);
- body->integrateVelocities( timeStep);
- body->predictIntegratedTransform(timeStep,body->m_interpolationWorldTransform);
- }
- }
-
- }
+ CcdPhysicsController* ctrl = GetPhysicsController(i);
+ ctrl->SynchronizeMotionStates(timeStep);
}
-#ifdef USE_QUICKPROF
- Profiler::endBlock("predictIntegratedTransform");
-#endif //USE_QUICKPROF
-
- OverlappingPairCache* scene = m_collisionWorld->GetPairCache();
-
-
- //
- // collision detection (?)
- //
-
-
-#ifdef USE_QUICKPROF
- Profiler::beginBlock("DispatchAllCollisionPairs");
-#endif //USE_QUICKPROF
-
-
- int numsubstep = m_numIterations;
-
-
- DispatcherInfo dispatchInfo;
- dispatchInfo.m_timeStep = timeStep;
- dispatchInfo.m_stepCount = 0;
- dispatchInfo.m_enableSatConvex = m_enableSatCollisionDetection;
- dispatchInfo.m_debugDraw = this->m_debugDrawer;
-
- scene->RefreshOverlappingPairs();
- GetCollisionWorld()->GetDispatcher()->DispatchAllCollisionPairs(&scene->GetOverlappingPair(0),scene->GetNumOverlappingPairs(),dispatchInfo);
-
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("DispatchAllCollisionPairs");
-#endif //USE_QUICKPROF
-
-
- int numRigidBodies = m_controllers.size();
-
+ m_dynamicsWorld->stepSimulation(timeStep);
- m_islandManager->UpdateActivationState(GetCollisionWorld(),GetCollisionWorld()->GetDispatcher());
-
- {
- int i;
- int numConstraints = m_constraints.size();
- for (i=0;i< numConstraints ; i++ )
- {
- TypedConstraint* constraint = m_constraints[i];
-
- const RigidBody* colObj0 = &constraint->GetRigidBodyA();
- const RigidBody* colObj1 = &constraint->GetRigidBodyB();
-
- if (((colObj0) && ((colObj0)->mergesSimulationIslands())) &&
- ((colObj1) && ((colObj1)->mergesSimulationIslands())))
- {
- if (colObj0->IsActive() || colObj1->IsActive())
- {
-
- m_islandManager->GetUnionFind().unite((colObj0)->m_islandTag1,
- (colObj1)->m_islandTag1);
- }
- }
- }
- }
-
- m_islandManager->StoreIslandActivationState(GetCollisionWorld());
-
-
- //contacts
-#ifdef USE_QUICKPROF
- Profiler::beginBlock("SolveConstraint");
-#endif //USE_QUICKPROF
-
-
- //solve the regular constraints (point 2 point, hinge, etc)
-
- for (int g=0;g<numsubstep;g++)
- {
- //
- // constraint solving
- //
-
-
- int i;
- int numConstraints = m_constraints.size();
-
- //point to point constraints
- for (i=0;i< numConstraints ; i++ )
- {
- TypedConstraint* constraint = m_constraints[i];
-
- constraint->BuildJacobian();
- constraint->SolveConstraint( timeStep );
-
- }
-
-
- }
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("SolveConstraint");
-#endif //USE_QUICKPROF
-
- //solve the vehicles
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
- //vehicles
- int numVehicles = m_wrapperVehicles.size();
- for (int i=0;i<numVehicles;i++)
- {
- WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
- RaycastVehicle* vehicle = wrapperVehicle->GetVehicle();
- vehicle->UpdateVehicle( timeStep);
- }
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
-
- struct InplaceSolverIslandCallback : public SimulationIslandManager::IslandCallback
- {
-
- ContactSolverInfo& m_solverInfo;
- ConstraintSolver* m_solver;
- IDebugDraw* m_debugDrawer;
-
- InplaceSolverIslandCallback(
- ContactSolverInfo& solverInfo,
- ConstraintSolver* solver,
- IDebugDraw* debugDrawer)
- :m_solverInfo(solverInfo),
- m_solver(solver),
- m_debugDrawer(debugDrawer)
- {
-
- }
-
- virtual void ProcessIsland(PersistentManifold** manifolds,int numManifolds)
- {
- m_solver->SolveGroup( manifolds, numManifolds,m_solverInfo,m_debugDrawer);
- }
-
- };
-
-
- m_solverInfo.m_friction = 0.9f;
- m_solverInfo.m_numIterations = m_numIterations;
- m_solverInfo.m_timeStep = timeStep;
- m_solverInfo.m_restitution = 0.f;//m_restitution;
-
- InplaceSolverIslandCallback solverCallback(
- m_solverInfo,
- m_solver,
- m_debugDrawer);
-
-#ifdef USE_QUICKPROF
- Profiler::beginBlock("BuildAndProcessIslands");
-#endif //USE_QUICKPROF
-
- /// solve all the contact points and contact friction
- m_islandManager->BuildAndProcessIslands(GetCollisionWorld()->GetDispatcher(),m_collisionWorld->GetCollisionObjectArray(),&solverCallback);
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("BuildAndProcessIslands");
-
- Profiler::beginBlock("CallbackTriggers");
-#endif //USE_QUICKPROF
-
- CallbackTriggers();
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("CallbackTriggers");
-
-
- Profiler::beginBlock("proceedToTransform");
-
-#endif //USE_QUICKPROF
- {
-
-
-
- {
-
-
-
- UpdateAabbs(timeStep);
-
-
- float toi = 1.f;
-
-
-
- if (m_ccdMode == 3)
- {
- DispatcherInfo dispatchInfo;
- dispatchInfo.m_timeStep = timeStep;
- dispatchInfo.m_stepCount = 0;
- dispatchInfo.m_dispatchFunc = DispatcherInfo::DISPATCH_CONTINUOUS;
-
- //pairCache->RefreshOverlappingPairs();//??
- GetCollisionWorld()->GetDispatcher()->DispatchAllCollisionPairs(&scene->GetOverlappingPair(0),scene->GetNumOverlappingPairs(),dispatchInfo);
-
- toi = dispatchInfo.m_timeOfImpact;
-
- }
-
-
-
- //
- // integrating solution
- //
-
- {
-
- std::vector<CcdPhysicsController*>::iterator i;
-
- for (i=m_controllers.begin();
- !(i==m_controllers.end()); i++)
- {
-
- CcdPhysicsController* ctrl = *i;
-
- SimdTransform predictedTrans;
- RigidBody* body = ctrl->GetRigidBody();
-
- if (body->IsActive())
- {
-
- if (!body->IsStatic())
- {
- if (body->m_hitFraction < 1.f)
- {
- //set velocity to zero... until we have proper CCD integrated
- body->setLinearVelocity(body->getLinearVelocity()*0.5f);
- }
- body->predictIntegratedTransform(timeStep* toi, predictedTrans);
- body->proceedToTransform( predictedTrans);
- }
-
- }
- }
-
- }
-
-
-
-
-
- //
- // disable sleeping physics objects
- //
-
- std::vector<CcdPhysicsController*> m_sleepingControllers;
-
- std::vector<CcdPhysicsController*>::iterator i;
-
- for (i=m_controllers.begin();
- !(i==m_controllers.end()); i++)
- {
- CcdPhysicsController* ctrl = (*i);
- RigidBody* body = ctrl->GetRigidBody();
-
- ctrl->UpdateDeactivation(timeStep);
-
-
- if (ctrl->wantsSleeping())
- {
- if (body->GetActivationState() == ACTIVE_TAG)
- body->SetActivationState( WANTS_DEACTIVATION );
- } else
- {
- if (body->GetActivationState() != DISABLE_DEACTIVATION)
- body->SetActivationState( ACTIVE_TAG );
- }
-
- if (useIslands)
- {
- if (body->GetActivationState() == ISLAND_SLEEPING)
- {
- m_sleepingControllers.push_back(ctrl);
- }
- } else
- {
- if (ctrl->wantsSleeping())
- {
- m_sleepingControllers.push_back(ctrl);
- }
- }
- }
-
-
-
-
- }
-
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("proceedToTransform");
-
- Profiler::beginBlock("SyncMotionStates");
-#endif //USE_QUICKPROF
-
- SyncMotionStates(timeStep);
-
-#ifdef USE_QUICKPROF
- Profiler::endBlock("SyncMotionStates");
-
- Profiler::endProfilingCycle();
-#endif //USE_QUICKPROF
-
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
- //sync wheels for vehicles
- int numVehicles = m_wrapperVehicles.size();
- for (int i=0;i<numVehicles;i++)
- {
- WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
-
- wrapperVehicle->SyncWheels();
- }
-#endif //NEW_BULLET_VEHICLE_SUPPORT
- }
-
return true;
}
+
void CcdPhysicsEnvironment::setDebugMode(int debugMode)
{
if (m_debugDrawer){
- m_debugDrawer->SetDebugMode(debugMode);
+ m_debugDrawer->setDebugMode(debugMode);
}
}
@@ -1001,9 +474,10 @@ void CcdPhysicsEnvironment::setDeactivationAngularTreshold(float angTresh)
{
gAngularSleepingTreshold = angTresh;
}
+
void CcdPhysicsEnvironment::setContactBreakingTreshold(float contactBreakingTreshold)
{
- gContactBreakingTreshold = contactBreakingTreshold;
+ gContactBreakingThreshold = contactBreakingTreshold;
}
@@ -1049,7 +523,7 @@ void CcdPhysicsEnvironment::setSolverType(int solverType)
if (m_solverType != solverType)
{
- m_solver = new SequentialImpulseConstraintSolver();
+ m_solver = new btSequentialImpulseConstraintSolver();
break;
}
@@ -1073,296 +547,46 @@ void CcdPhysicsEnvironment::setSolverType(int solverType)
-void CcdPhysicsEnvironment::SyncMotionStates(float timeStep)
-{
- std::vector<CcdPhysicsController*>::iterator i;
-
- //
- // synchronize the physics and graphics transformations
- //
-
- for (i=m_controllers.begin();
- !(i==m_controllers.end()); i++)
- {
- CcdPhysicsController* ctrl = (*i);
- ctrl->SynchronizeMotionStates(timeStep);
-
- }
-}
void CcdPhysicsEnvironment::setGravity(float x,float y,float z)
{
- m_gravity = SimdVector3(x,y,z);
-
- std::vector<CcdPhysicsController*>::iterator i;
+ m_gravity = btVector3(x,y,z);
+ m_dynamicsWorld->setGravity(m_gravity);
- //todo: review this gravity stuff
- for (i=m_controllers.begin();
- !(i==m_controllers.end()); i++)
- {
-
- CcdPhysicsController* ctrl = (*i);
- ctrl->GetRigidBody()->setGravity(m_gravity);
-
- }
}
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
-class DefaultVehicleRaycaster : public VehicleRaycaster
-{
- CcdPhysicsEnvironment* m_physEnv;
- PHY_IPhysicsController* m_chassis;
-
-public:
- DefaultVehicleRaycaster(CcdPhysicsEnvironment* physEnv,PHY_IPhysicsController* chassis):
- m_physEnv(physEnv),
- m_chassis(chassis)
- {
- }
-
- /* struct VehicleRaycasterResult
- {
- VehicleRaycasterResult() :m_distFraction(-1.f){};
- SimdVector3 m_hitPointInWorld;
- SimdVector3 m_hitNormalInWorld;
- SimdScalar m_distFraction;
- };
- */
- virtual void* CastRay(const SimdVector3& from,const SimdVector3& to, VehicleRaycasterResult& result)
- {
-
-
- float hit[3];
- float normal[3];
-
- PHY_IPhysicsController* ignore = m_chassis;
- void* hitObject = m_physEnv->rayTest(ignore,from.x(),from.y(),from.z(),to.x(),to.y(),to.z(),hit[0],hit[1],hit[2],normal[0],normal[1],normal[2]);
- if (hitObject)
- {
- result.m_hitPointInWorld[0] = hit[0];
- result.m_hitPointInWorld[1] = hit[1];
- result.m_hitPointInWorld[2] = hit[2];
- result.m_hitNormalInWorld[0] = normal[0];
- result.m_hitNormalInWorld[1] = normal[1];
- result.m_hitNormalInWorld[2] = normal[2];
- result.m_hitNormalInWorld.normalize();
- //calc fraction? or put it in the interface?
- //calc for now
-
- result.m_distFraction = (result.m_hitPointInWorld-from).length() / (to-from).length();
- //some safety for 'explosion' due to sudden penetration of the full 'ray'
- /* if (result.m_distFraction<0.1)
- {
- printf("Vehicle Raycast: avoided instability due to penetration. Consider moving the connection points deeper inside vehicle chassis");
- result.m_distFraction = 1.f;
- hitObject = 0;
- }
- */
-
- /* if (result.m_distFraction>1.)
- {
- printf("Vehicle Raycast: avoided instability 1Consider moving the connection points deeper inside vehicle chassis");
- result.m_distFraction = 1.f;
- hitObject = 0;
- }
- */
-
-
-
- }
- //?
- return hitObject;
- }
-};
-#endif //NEW_BULLET_VEHICLE_SUPPORT
static int gConstraintUid = 1;
-int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl0,class PHY_IPhysicsController* ctrl1,PHY_ConstraintType type,
- float pivotX,float pivotY,float pivotZ,
- float axisX,float axisY,float axisZ)
-{
-
-
- CcdPhysicsController* c0 = (CcdPhysicsController*)ctrl0;
- CcdPhysicsController* c1 = (CcdPhysicsController*)ctrl1;
-
- RigidBody* rb0 = c0 ? c0->GetRigidBody() : 0;
- RigidBody* rb1 = c1 ? c1->GetRigidBody() : 0;
-
- ASSERT(rb0);
-
- SimdVector3 pivotInA(pivotX,pivotY,pivotZ);
- SimdVector3 pivotInB = rb1 ? rb1->getCenterOfMassTransform().inverse()(rb0->getCenterOfMassTransform()(pivotInA)) : pivotInA;
- SimdVector3 axisInA(axisX,axisY,axisZ);
- SimdVector3 axisInB = rb1 ?
- (rb1->getCenterOfMassTransform().getBasis().inverse()*(rb0->getCenterOfMassTransform().getBasis() * axisInA)) :
- rb0->getCenterOfMassTransform().getBasis() * axisInA;
-
- bool angularOnly = false;
-
- switch (type)
- {
- case PHY_POINT2POINT_CONSTRAINT:
- {
-
- Point2PointConstraint* p2p = 0;
-
- if (rb1)
- {
- p2p = new Point2PointConstraint(*rb0,
- *rb1,pivotInA,pivotInB);
- } else
- {
- p2p = new Point2PointConstraint(*rb0,
- pivotInA);
- }
-
- m_constraints.push_back(p2p);
- p2p->SetUserConstraintId(gConstraintUid++);
- p2p->SetUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return p2p->GetUserConstraintId();
-
- break;
- }
-
- case PHY_GENERIC_6DOF_CONSTRAINT:
- {
- Generic6DofConstraint* genericConstraint = 0;
-
- if (rb1)
- {
- SimdTransform frameInA;
- SimdTransform frameInB;
-
- SimdVector3 axis1, axis2;
- SimdPlaneSpace1( axisInA, axis1, axis2 );
-
- frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(),
- axisInA.y(), axis1.y(), axis2.y(),
- axisInA.z(), axis1.z(), axis2.z() );
-
-
- SimdPlaneSpace1( axisInB, axis1, axis2 );
- frameInB.getBasis().setValue( axisInB.x(), axis1.x(), axis2.x(),
- axisInB.y(), axis1.y(), axis2.y(),
- axisInB.z(), axis1.z(), axis2.z() );
-
- frameInA.setOrigin( pivotInA );
- frameInB.setOrigin( pivotInB );
-
- genericConstraint = new Generic6DofConstraint(
- *rb0,*rb1,
- frameInA,frameInB);
-
-
- } else
- {
- // TODO: Implement single body case...
-
- }
-
-
- m_constraints.push_back(genericConstraint);
- genericConstraint->SetUserConstraintId(gConstraintUid++);
- genericConstraint->SetUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return genericConstraint->GetUserConstraintId();
-
- break;
- }
- case PHY_ANGULAR_CONSTRAINT:
- angularOnly = true;
-
-
- case PHY_LINEHINGE_CONSTRAINT:
- {
- HingeConstraint* hinge = 0;
-
- if (rb1)
- {
- hinge = new HingeConstraint(
- *rb0,
- *rb1,pivotInA,pivotInB,axisInA,axisInB);
-
-
- } else
- {
- hinge = new HingeConstraint(*rb0,
- pivotInA,axisInA);
-
- }
- hinge->setAngularOnly(angularOnly);
-
- m_constraints.push_back(hinge);
- hinge->SetUserConstraintId(gConstraintUid++);
- hinge->SetUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return hinge->GetUserConstraintId();
- break;
- }
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
-
- case PHY_VEHICLE_CONSTRAINT:
- {
- RaycastVehicle::VehicleTuning* tuning = new RaycastVehicle::VehicleTuning();
- RigidBody* chassis = rb0;
- DefaultVehicleRaycaster* raycaster = new DefaultVehicleRaycaster(this,ctrl0);
- RaycastVehicle* vehicle = new RaycastVehicle(*tuning,chassis,raycaster);
- WrapperVehicle* wrapperVehicle = new WrapperVehicle(vehicle,ctrl0);
- m_wrapperVehicles.push_back(wrapperVehicle);
- vehicle->SetUserConstraintId(gConstraintUid++);
- vehicle->SetUserConstraintType(type);
- return vehicle->GetUserConstraintId();
-
- break;
- };
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
- default:
- {
- }
- };
-
- //RigidBody& rbA,RigidBody& rbB, const SimdVector3& pivotInA,const SimdVector3& pivotInB
-
- return 0;
-
-}
-
-
-
-
//Following the COLLADA physics specification for constraints
int CcdPhysicsEnvironment::createUniversalD6Constraint(
class PHY_IPhysicsController* ctrlRef,class PHY_IPhysicsController* ctrlOther,
- SimdTransform& frameInA,
- SimdTransform& frameInB,
- const SimdVector3& linearMinLimits,
- const SimdVector3& linearMaxLimits,
- const SimdVector3& angularMinLimits,
- const SimdVector3& angularMaxLimits
+ btTransform& frameInA,
+ btTransform& frameInB,
+ const btVector3& linearMinLimits,
+ const btVector3& linearMaxLimits,
+ const btVector3& angularMinLimits,
+ const btVector3& angularMaxLimits
)
{
//we could either add some logic to recognize ball-socket and hinge, or let that up to the user
//perhaps some warning or hint that hinge/ball-socket is more efficient?
- Generic6DofConstraint* genericConstraint = 0;
+ btGeneric6DofConstraint* genericConstraint = 0;
CcdPhysicsController* ctrl0 = (CcdPhysicsController*) ctrlRef;
CcdPhysicsController* ctrl1 = (CcdPhysicsController*) ctrlOther;
- RigidBody* rb0 = ctrl0->GetRigidBody();
- RigidBody* rb1 = ctrl1->GetRigidBody();
+ btRigidBody* rb0 = ctrl0->GetRigidBody();
+ btRigidBody* rb1 = ctrl1->GetRigidBody();
if (rb1)
{
- genericConstraint = new Generic6DofConstraint(
+ genericConstraint = new btGeneric6DofConstraint(
*rb0,*rb1,
frameInA,frameInB);
genericConstraint->setLinearLowerLimit(linearMinLimits);
@@ -1378,11 +602,13 @@ int CcdPhysicsEnvironment::createUniversalD6Constraint(
if (genericConstraint)
{
- m_constraints.push_back(genericConstraint);
- genericConstraint->SetUserConstraintId(gConstraintUid++);
- genericConstraint->SetUserConstraintType(PHY_GENERIC_6DOF_CONSTRAINT);
+ // m_constraints.push_back(genericConstraint);
+ m_dynamicsWorld->addConstraint(genericConstraint);
+
+ genericConstraint->setUserConstraintId(gConstraintUid++);
+ genericConstraint->setUserConstraintType(PHY_GENERIC_6DOF_CONSTRAINT);
//64 bit systems can't cast pointer to int. could use size_t instead.
- return genericConstraint->GetUserConstraintId();
+ return genericConstraint->getUserConstraintId();
}
return 0;
}
@@ -1391,51 +617,49 @@ int CcdPhysicsEnvironment::createUniversalD6Constraint(
void CcdPhysicsEnvironment::removeConstraint(int constraintId)
{
- std::vector<TypedConstraint*>::iterator i;
-
- for (i=m_constraints.begin();
- !(i==m_constraints.end()); i++)
+
+ int i;
+ int numConstraints = m_dynamicsWorld->getNumConstraints();
+ for (i=0;i<numConstraints;i++)
{
- TypedConstraint* constraint = (*i);
- if (constraint->GetUserConstraintId() == constraintId)
+ btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
+ if (constraint->getUserConstraintId() == constraintId)
{
- std::swap(*i, m_constraints.back());
- m_constraints.pop_back();
+ m_dynamicsWorld->removeConstraint(constraint);
break;
}
}
-
}
- struct FilterClosestRayResultCallback : public CollisionWorld::ClosestRayResultCallback
- {
- PHY_IPhysicsController* m_ignoreClient;
+struct FilterClosestRayResultCallback : public btCollisionWorld::ClosestRayResultCallback
+{
+ PHY_IPhysicsController* m_ignoreClient;
- FilterClosestRayResultCallback (PHY_IPhysicsController* ignoreClient,const SimdVector3& rayFrom,const SimdVector3& rayTo)
- : CollisionWorld::ClosestRayResultCallback(rayFrom,rayTo),
- m_ignoreClient(ignoreClient)
- {
+ FilterClosestRayResultCallback (PHY_IPhysicsController* ignoreClient,const btVector3& rayFrom,const btVector3& rayTo)
+ : btCollisionWorld::ClosestRayResultCallback(rayFrom,rayTo),
+ m_ignoreClient(ignoreClient)
+ {
- }
+ }
- virtual ~FilterClosestRayResultCallback()
- {
- }
+ virtual ~FilterClosestRayResultCallback()
+ {
+ }
- virtual float AddSingleResult(const CollisionWorld::LocalRayResult& rayResult)
- {
- CcdPhysicsController* curHit = static_cast<CcdPhysicsController*>(rayResult.m_collisionObject->m_userPointer);
- //ignore client...
- if (curHit != m_ignoreClient)
- {
- //if valid
- return ClosestRayResultCallback::AddSingleResult(rayResult);
- }
- return m_closestHitFraction;
+ virtual float AddSingleResult( btCollisionWorld::LocalRayResult& rayResult)
+ {
+ CcdPhysicsController* curHit = static_cast<CcdPhysicsController*>(rayResult.m_collisionObject->getUserPointer());
+ //ignore client...
+ if (curHit != m_ignoreClient)
+ {
+ //if valid
+ return ClosestRayResultCallback::AddSingleResult(rayResult);
}
+ return m_closestHitFraction;
+ }
- };
+};
PHY_IPhysicsController* CcdPhysicsEnvironment::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)
@@ -1444,23 +668,23 @@ PHY_IPhysicsController* CcdPhysicsEnvironment::rayTest(PHY_IPhysicsController* i
float minFraction = 1.f;
- SimdVector3 rayFrom(fromX,fromY,fromZ);
- SimdVector3 rayTo(toX,toY,toZ);
+ btVector3 rayFrom(fromX,fromY,fromZ);
+ btVector3 rayTo(toX,toY,toZ);
- SimdVector3 hitPointWorld,normalWorld;
+ btVector3 hitPointWorld,normalWorld;
//Either Ray Cast with or without filtering
- //CollisionWorld::ClosestRayResultCallback rayCallback(rayFrom,rayTo);
+ //btCollisionWorld::ClosestRayResultCallback rayCallback(rayFrom,rayTo);
FilterClosestRayResultCallback rayCallback(ignoreClient,rayFrom,rayTo);
PHY_IPhysicsController* nearestHit = 0;
- m_collisionWorld->RayTest(rayFrom,rayTo,rayCallback);
+ m_dynamicsWorld->rayTest(rayFrom,rayTo,rayCallback);
if (rayCallback.HasHit())
{
- nearestHit = static_cast<CcdPhysicsController*>(rayCallback.m_collisionObject->m_userPointer);
+ nearestHit = static_cast<CcdPhysicsController*>(rayCallback.m_collisionObject->getUserPointer());
hitX = rayCallback.m_hitPointWorld.getX();
hitY = rayCallback.m_hitPointWorld.getY();
hitZ = rayCallback.m_hitPointWorld.getZ();
@@ -1490,9 +714,9 @@ void CcdPhysicsEnvironment::getContactPoint(int i,float& hitX,float& hitY,float&
-BroadphaseInterface* CcdPhysicsEnvironment::GetBroadphase()
+btBroadphaseInterface* CcdPhysicsEnvironment::getBroadphase()
{
- return m_collisionWorld->GetBroadphase();
+ return m_dynamicsWorld->getBroadphase();
}
@@ -1510,9 +734,9 @@ CcdPhysicsEnvironment::~CcdPhysicsEnvironment()
//first delete scene, then dispatcher, because pairs have to release manifolds on the dispatcher
//delete m_dispatcher;
- delete m_collisionWorld;
+ delete m_dynamicsWorld;
- delete m_islandManager;
+
}
@@ -1533,18 +757,22 @@ CcdPhysicsController* CcdPhysicsEnvironment::GetPhysicsController( int index)
-TypedConstraint* CcdPhysicsEnvironment::getConstraintById(int constraintId)
+btTypedConstraint* CcdPhysicsEnvironment::getConstraintById(int constraintId)
{
+ return 0;
+ /*
int numConstraint = m_constraints.size();
int i;
for (i=0;i<numConstraint;i++)
{
- TypedConstraint* constraint = m_constraints[i];
- if (constraint->GetUserConstraintId()==constraintId)
+ btTypedConstraint* constraint = m_constraints[i];
+ if (constraint->getUserConstraintId()==constraintId)
{
return constraint;
}
}
+ */
+
return 0;
}
@@ -1627,32 +855,32 @@ void CcdPhysicsEnvironment::CallbackTriggers()
CcdPhysicsController* ctrl0=0,*ctrl1=0;
- if (m_triggerCallbacks[PHY_OBJECT_RESPONSE] || (m_debugDrawer && (m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_DrawContactPoints)))
+ if (m_triggerCallbacks[PHY_OBJECT_RESPONSE] || (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints)))
{
//walk over all overlapping pairs, and if one of the involved bodies is registered for trigger callback, perform callback
- int numManifolds = m_collisionWorld->GetDispatcher()->GetNumManifolds();
+ int numManifolds = m_dynamicsWorld->getDispatcher()->getNumManifolds();
for (int i=0;i<numManifolds;i++)
{
- PersistentManifold* manifold = m_collisionWorld->GetDispatcher()->GetManifoldByIndexInternal(i);
- int numContacts = manifold->GetNumContacts();
+ btPersistentManifold* manifold = m_dynamicsWorld->getDispatcher()->getManifoldByIndexInternal(i);
+ int numContacts = manifold->getNumContacts();
if (numContacts)
{
- if (m_debugDrawer && (m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_DrawContactPoints))
+ if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints))
{
for (int j=0;j<numContacts;j++)
{
- SimdVector3 color(1,0,0);
- const ManifoldPoint& cp = manifold->GetContactPoint(j);
+ btVector3 color(1,0,0);
+ const btManifoldPoint& cp = manifold->getContactPoint(j);
if (m_debugDrawer)
- m_debugDrawer->DrawContactPoint(cp.m_positionWorldOnB,cp.m_normalWorldOnB,cp.GetDistance(),cp.GetLifeTime(),color);
+ m_debugDrawer->drawContactPoint(cp.m_positionWorldOnB,cp.m_normalWorldOnB,cp.getDistance(),cp.getLifeTime(),color);
}
}
- RigidBody* obj0 = static_cast<RigidBody* >(manifold->GetBody0());
- RigidBody* obj1 = static_cast<RigidBody* >(manifold->GetBody1());
+ btRigidBody* obj0 = static_cast<btRigidBody* >(manifold->getBody0());
+ btRigidBody* obj1 = static_cast<btRigidBody* >(manifold->getBody1());
- //m_userPointer is set in 'addPhysicsController
- CcdPhysicsController* ctrl0 = static_cast<CcdPhysicsController*>(obj0->m_userPointer);
- CcdPhysicsController* ctrl1 = static_cast<CcdPhysicsController*>(obj1->m_userPointer);
+ //m_internalOwner is set in 'addPhysicsController'
+ CcdPhysicsController* ctrl0 = static_cast<CcdPhysicsController*>(obj0->getUserPointer());
+ CcdPhysicsController* ctrl1 = static_cast<CcdPhysicsController*>(obj1->getUserPointer());
std::vector<CcdPhysicsController*>::iterator i =
std::find(m_triggerControllers.begin(), m_triggerControllers.end(), ctrl0);
@@ -1692,7 +920,7 @@ PHY_IVehicle* CcdPhysicsEnvironment::getVehicleConstraint(int constraintId)
for (i=0;i<numVehicles;i++)
{
WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
- if (wrapperVehicle->GetVehicle()->GetUserConstraintId() == constraintId)
+ if (wrapperVehicle->GetVehicle()->getUserConstraintId() == constraintId)
return wrapperVehicle;
}
@@ -1702,132 +930,209 @@ PHY_IVehicle* CcdPhysicsEnvironment::getVehicleConstraint(int constraintId)
#endif //NEW_BULLET_VEHICLE_SUPPORT
+int currentController = 0;
+int numController = 0;
+
-void CcdPhysicsEnvironment::UpdateAabbs(float timeStep)
+
+
+PHY_IPhysicsController* CcdPhysicsEnvironment::CreateSphereController(float radius,const PHY__Vector3& position)
{
- std::vector<CcdPhysicsController*>::iterator i;
- BroadphaseInterface* scene = GetBroadphase();
-
- //
- // update aabbs, only for moving objects (!)
- //
- for (i=m_controllers.begin();
- !(i==m_controllers.end()); i++)
+
+ CcdConstructionInfo cinfo;
+ cinfo.m_collisionShape = new btSphereShape(radius);
+ cinfo.m_MotionState = 0;
+ cinfo.m_physicsEnv = this;
+ cinfo.m_collisionFlags |= btCollisionObject::CF_NO_CONTACT_RESPONSE;
+ DefaultMotionState* motionState = new DefaultMotionState();
+ cinfo.m_MotionState = motionState;
+ motionState->m_worldTransform.setIdentity();
+ motionState->m_worldTransform.setOrigin(btVector3(position[0],position[1],position[2]));
+
+ CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo);
+
+
+ return sphereController;
+}
+
+int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl0,class PHY_IPhysicsController* ctrl1,PHY_ConstraintType type,
+ float pivotX,float pivotY,float pivotZ,
+ float axisX,float axisY,float axisZ)
+{
+
+
+ CcdPhysicsController* c0 = (CcdPhysicsController*)ctrl0;
+ CcdPhysicsController* c1 = (CcdPhysicsController*)ctrl1;
+
+ btRigidBody* rb0 = c0 ? c0->GetRigidBody() : 0;
+ btRigidBody* rb1 = c1 ? c1->GetRigidBody() : 0;
+
+ bool rb0static = rb0 ? rb0->isStaticOrKinematicObject() : true;
+ bool rb1static = rb1 ? rb1->isStaticOrKinematicObject() : true;
+
+
+ if (rb0static && rb1static)
+ return 0;
+
+
+ ASSERT(rb0);
+
+ btVector3 pivotInA(pivotX,pivotY,pivotZ);
+ btVector3 pivotInB = rb1 ? rb1->getCenterOfMassTransform().inverse()(rb0->getCenterOfMassTransform()(pivotInA)) : pivotInA;
+ btVector3 axisInA(axisX,axisY,axisZ);
+ btVector3 axisInB = rb1 ?
+ (rb1->getCenterOfMassTransform().getBasis().inverse()*(rb0->getCenterOfMassTransform().getBasis() * axisInA)) :
+ rb0->getCenterOfMassTransform().getBasis() * axisInA;
+
+ bool angularOnly = false;
+
+ switch (type)
+ {
+ case PHY_POINT2POINT_CONSTRAINT:
+ {
+
+ btPoint2PointConstraint* p2p = 0;
+
+ if (rb1)
{
- CcdPhysicsController* ctrl = (*i);
- RigidBody* body = ctrl->GetRigidBody();
+ p2p = new btPoint2PointConstraint(*rb0,
+ *rb1,pivotInA,pivotInB);
+ } else
+ {
+ p2p = new btPoint2PointConstraint(*rb0,
+ pivotInA);
+ }
+ m_dynamicsWorld->addConstraint(p2p);
+// m_constraints.push_back(p2p);
- SimdPoint3 minAabb,maxAabb;
- CollisionShape* shapeinterface = ctrl->GetCollisionShape();
+ p2p->setUserConstraintId(gConstraintUid++);
+ p2p->setUserConstraintType(type);
+ //64 bit systems can't cast pointer to int. could use size_t instead.
+ return p2p->getUserConstraintId();
+ break;
+ }
+ case PHY_GENERIC_6DOF_CONSTRAINT:
+ {
+ btGeneric6DofConstraint* genericConstraint = 0;
- shapeinterface->CalculateTemporalAabb(body->getCenterOfMassTransform(),
- body->getLinearVelocity(),
- //body->getAngularVelocity(),
- SimdVector3(0.f,0.f,0.f),//no angular effect for now //body->getAngularVelocity(),
- timeStep,minAabb,maxAabb);
+ if (rb1)
+ {
+ btTransform frameInA;
+ btTransform frameInB;
+
+ btVector3 axis1, axis2;
+ btPlaneSpace1( axisInA, axis1, axis2 );
+ frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(),
+ axisInA.y(), axis1.y(), axis2.y(),
+ axisInA.z(), axis1.z(), axis2.z() );
- SimdVector3 manifoldExtraExtents(gContactBreakingTreshold,gContactBreakingTreshold,gContactBreakingTreshold);
- minAabb -= manifoldExtraExtents;
- maxAabb += manifoldExtraExtents;
+
+ btPlaneSpace1( axisInB, axis1, axis2 );
+ frameInB.getBasis().setValue( axisInB.x(), axis1.x(), axis2.x(),
+ axisInB.y(), axis1.y(), axis2.y(),
+ axisInB.z(), axis1.z(), axis2.z() );
- BroadphaseProxy* bp = body->m_broadphaseHandle;
- if (bp)
- {
+ frameInA.setOrigin( pivotInA );
+ frameInB.setOrigin( pivotInB );
- SimdVector3 color (1,1,0);
-
- if (m_debugDrawer)
- {
- //draw aabb
- switch (body->GetActivationState())
- {
- case ISLAND_SLEEPING:
- {
- color.setValue(1,1,1);
- break;
- }
- case WANTS_DEACTIVATION:
- {
- color.setValue(0,0,1);
- break;
- }
- case ACTIVE_TAG:
- {
- break;
- }
- case DISABLE_DEACTIVATION:
- {
- color.setValue(1,0,1);
- };
-
- };
-
- if (m_debugDrawer->GetDebugMode() & IDebugDraw::DBG_DrawAabb)
- {
- DrawAabb(m_debugDrawer,minAabb,maxAabb,color);
- }
- }
+ genericConstraint = new btGeneric6DofConstraint(
+ *rb0,*rb1,
+ frameInA,frameInB);
+
+ } else
+ {
+ // TODO: Implement single body case...
+
+ }
- if ( (maxAabb-minAabb).length2() < 1e12f)
- {
- scene->SetAabb(bp,minAabb,maxAabb);
- } else
- {
- //something went wrong, investigate
- //removeCcdPhysicsController(ctrl);
- body->SetActivationState(DISABLE_SIMULATION);
-
- static bool reportMe = true;
- if (reportMe)
- {
- reportMe = false;
- printf("Overflow in AABB, object removed from simulation \n");
- printf("If you can reproduce this, please email bugs@continuousphysics.com\n");
- printf("Please include above information, your Platform, version of OS.\n");
- printf("Thanks.\n");
- }
-
- }
- }
+ //m_constraints.push_back(genericConstraint);
+ m_dynamicsWorld->addConstraint(genericConstraint);
+ genericConstraint->setUserConstraintId(gConstraintUid++);
+ genericConstraint->setUserConstraintType(type);
+ //64 bit systems can't cast pointer to int. could use size_t instead.
+ return genericConstraint->getUserConstraintId();
+
+ break;
+ }
+ case PHY_ANGULAR_CONSTRAINT:
+ angularOnly = true;
+
+
+ case PHY_LINEHINGE_CONSTRAINT:
+ {
+ btHingeConstraint* hinge = 0;
+
+ if (rb1)
+ {
+ hinge = new btHingeConstraint(
+ *rb0,
+ *rb1,pivotInA,pivotInB,axisInA,axisInB);
+
+
+ } else
+ {
+ hinge = new btHingeConstraint(*rb0,
+ pivotInA,axisInA);
+
}
-}
+ hinge->setAngularOnly(angularOnly);
-PHY_IPhysicsController* CcdPhysicsEnvironment::CreateSphereController(float radius,const PHY__Vector3& position)
-{
-
- CcdConstructionInfo cinfo;
- cinfo.m_collisionShape = new SphereShape(radius);
- cinfo.m_MotionState = 0;
- cinfo.m_physicsEnv = this;
- cinfo.m_collisionFlags |= CollisionObject::noContactResponse;
- DefaultMotionState* motionState = new DefaultMotionState();
- cinfo.m_MotionState = motionState;
- motionState->m_worldTransform.setIdentity();
- motionState->m_worldTransform.setOrigin(SimdVector3(position[0],position[1],position[2]));
+ //m_constraints.push_back(hinge);
+ m_dynamicsWorld->addConstraint(hinge);
+ hinge->setUserConstraintId(gConstraintUid++);
+ hinge->setUserConstraintType(type);
+ //64 bit systems can't cast pointer to int. could use size_t instead.
+ return hinge->getUserConstraintId();
+ break;
+ }
+#ifdef NEW_BULLET_VEHICLE_SUPPORT
- CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo);
-
+ case PHY_VEHICLE_CONSTRAINT:
+ {
+ btRaycastVehicle::btVehicleTuning* tuning = new btRaycastVehicle::btVehicleTuning();
+ btRigidBody* chassis = rb0;
+ btDefaultVehicleRaycaster* raycaster = new btDefaultVehicleRaycaster(m_dynamicsWorld);
+ btRaycastVehicle* vehicle = new btRaycastVehicle(*tuning,chassis,raycaster);
+ WrapperVehicle* wrapperVehicle = new WrapperVehicle(vehicle,ctrl0);
+ m_wrapperVehicles.push_back(wrapperVehicle);
+ m_dynamicsWorld->addVehicle(vehicle);
+ vehicle->setUserConstraintId(gConstraintUid++);
+ vehicle->setUserConstraintType(type);
+ return vehicle->getUserConstraintId();
+
+ break;
+ };
+#endif //NEW_BULLET_VEHICLE_SUPPORT
+
+ default:
+ {
+ }
+ };
+
+ //btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB
+
+ return 0;
- return sphereController;
}
+
PHY_IPhysicsController* CcdPhysicsEnvironment::CreateConeController(float coneradius,float coneheight)
{
CcdConstructionInfo cinfo;
- cinfo.m_collisionShape = new ConeShape(coneradius,coneheight);
+ cinfo.m_collisionShape = new btConeShape(coneradius,coneheight);
cinfo.m_MotionState = 0;
cinfo.m_physicsEnv = this;
DefaultMotionState* motionState = new DefaultMotionState();
cinfo.m_MotionState = motionState;
motionState->m_worldTransform.setIdentity();
-// motionState->m_worldTransform.setOrigin(SimdVector3(position[0],position[1],position[2]));
+// motionState->m_worldTransform.setOrigin(btVector3(position[0],position[1],position[2]));
CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo);
@@ -1837,16 +1142,16 @@ PHY_IPhysicsController* CcdPhysicsEnvironment::CreateConeController(float conera
float CcdPhysicsEnvironment::getAppliedImpulse(int constraintid)
{
- std::vector<TypedConstraint*>::iterator i;
-
- for (i=m_constraints.begin();
- !(i==m_constraints.end()); i++)
+ int i;
+ int numConstraints = m_dynamicsWorld->getNumConstraints();
+ for (i=0;i<numConstraints;i++)
{
- TypedConstraint* constraint = (*i);
- if (constraint->GetUserConstraintId() == constraintid)
+ btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
+ if (constraint->getUserConstraintId() == constraintid)
{
- return constraint->GetAppliedImpulse();
+ return constraint->getAppliedImpulse();
}
}
+
return 0.f;
}
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h
index a1f075e3882..7911c3d1ed9 100644
--- a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h
+++ b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h
@@ -19,41 +19,42 @@ subject to the following restrictions:
#include "PHY_IPhysicsEnvironment.h"
#include <vector>
class CcdPhysicsController;
-#include "SimdVector3.h"
-#include "SimdTransform.h"
+#include "LinearMath/btVector3.h"
+#include "LinearMath/btTransform.h"
-class TypedConstraint;
-class SimulationIslandManager;
-class CollisionDispatcher;
-class Dispatcher;
-//#include "BroadphaseInterface.h"
+class btTypedConstraint;
+class btSimulationIslandManager;
+class btCollisionDispatcher;
+class btDispatcher;
+//#include "btBroadphaseInterface.h"
//switch on/off new vehicle support
#define NEW_BULLET_VEHICLE_SUPPORT 1
-#include "ConstraintSolver/ContactSolverInfo.h"
+#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 experimental mainloop for physics simulation using optional continuous collision detection.
+/// CcdPhysicsEnvironment is an experimental mainloop for physics simulation using optional continuous collision detection.
/// Physics Environment takes care of stepping the simulation and is a container for physics entities.
/// It stores rigidbodies,constraints, materials etc.
/// 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;
@@ -66,12 +67,11 @@ protected:
int m_profileTimings;
bool m_enableSatCollisionDetection;
- ContactSolverInfo m_solverInfo;
+ btContactSolverInfo m_solverInfo;
- SimulationIslandManager* m_islandManager;
public:
- CcdPhysicsEnvironment(Dispatcher* dispatcher=0, OverlappingPairCache* pairCache=0);
+ CcdPhysicsEnvironment(btDispatcher* dispatcher=0, btOverlappingPairCache* pairCache=0);
virtual ~CcdPhysicsEnvironment();
@@ -81,7 +81,7 @@ protected:
/// Perform an integration step of duration 'timeStep'.
- virtual void setDebugDrawer(IDebugDraw* debugDrawer)
+ virtual void setDebugDrawer(btIDebugDraw* debugDrawer)
{
m_debugDrawer = debugDrawer;
}
@@ -107,7 +107,7 @@ protected:
virtual void endFrame() {};
/// Perform an integration step of duration 'timeStep'.
virtual bool proceedDeltaTime(double curTime,float timeStep);
- virtual bool proceedDeltaTimeOneStep(float timeStep);
+// virtual bool proceedDeltaTimeOneStep(float timeStep);
virtual void setFixedTimeStep(bool useFixedTimeStep,float fixedTimeStep){};
//returns 0.f if no fixed timestep is used
@@ -126,20 +126,20 @@ 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
);
virtual void removeConstraint(int constraintid);
-
virtual float getAppliedImpulse(int constraintid);
+
virtual void CallbackTriggers();
@@ -153,7 +153,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);
@@ -182,7 +182,7 @@ protected:
void removeCcdPhysicsController(CcdPhysicsController* ctrl);
- BroadphaseInterface* GetBroadphase();
+ btBroadphaseInterface* getBroadphase();
@@ -198,40 +198,21 @@ protected:
m_enableSatCollisionDetection = enableSat;
}
- void UpdateAabbs(float timeStep);
-
+
int GetNumControllers();
CcdPhysicsController* GetPhysicsController( int index);
- const PersistentManifold* GetManifold(int index) const;
-
- std::vector<TypedConstraint*> m_constraints;
+ const btPersistentManifold* GetManifold(int index) const;
+
void SyncMotionStates(float timeStep);
- class CollisionWorld* GetCollisionWorld()
- {
- return m_collisionWorld;
- }
-
- const class CollisionWorld* GetCollisionWorld() const
- {
- return m_collisionWorld;
- }
-
- SimulationIslandManager* GetSimulationIslandManager()
- {
- return m_islandManager;
- }
-
- const SimulationIslandManager* GetSimulationIslandManager() const
- {
- return m_islandManager;
- }
+
+ class btConstraintSolver* GetConstraintSolver();
protected:
@@ -247,9 +228,9 @@ protected:
std::vector<WrapperVehicle*> m_wrapperVehicles;
- class CollisionWorld* m_collisionWorld;
+ class btDynamicsWorld* m_dynamicsWorld;
- class ConstraintSolver* m_solver;
+ class btConstraintSolver* m_solver;
bool m_scalingPropagated;
diff --git a/source/gameengine/Physics/common/PHY_IVehicle.h b/source/gameengine/Physics/common/PHY_IVehicle.h
index d5566ff5bb3..498df0dd840 100644
--- a/source/gameengine/Physics/common/PHY_IVehicle.h
+++ b/source/gameengine/Physics/common/PHY_IVehicle.h
@@ -50,6 +50,7 @@ public:
virtual void SetRollInfluence(float rollInfluence,int wheelIndex) = 0;
+ virtual void SetCoordinateSystem(int rightIndex,int upIndex,int forwardIndex) =0;
};