confusion about memory management, and removed obsolete PhysicsInterface code.todo: updated the demos that still use this code

This commit is contained in:
ejcoumans
2006-09-29 19:57:23 +00:00
parent 0d7c960eb6
commit 14397a2f72
39 changed files with 74 additions and 5700 deletions

View File

@@ -1 +0,0 @@
SUBDIRS( CcdPhysics Common )

View File

@@ -1,11 +0,0 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/CcdPhysics }
)
ADD_LIBRARY(LibCcdPhysicsInterface
CcdPhysicsController.cpp
CcdPhysicsEnvironment.cpp
ParallelIslandDispatcher.cpp
ParallelPhysicsEnvironment.cpp
SimulationIsland.cpp
)

View File

@@ -1,112 +0,0 @@
# Microsoft Developer Studio Project File - Name="CcdPhysics" - Package Owner=<4>
# Microsoft Developer Studio Generated Build File, Format Version 6.00
# ** DO NOT EDIT **
# TARGTYPE "Win32 (x86) Static Library" 0x0104
CFG=CcdPhysics - Win32 Debug
!MESSAGE This is not a valid makefile. To build this project using NMAKE,
!MESSAGE use the Export Makefile command and run
!MESSAGE
!MESSAGE NMAKE /f "CcdPhysics.mak".
!MESSAGE
!MESSAGE You can specify a configuration when running NMAKE
!MESSAGE by defining the macro CFG on the command line. For example:
!MESSAGE
!MESSAGE NMAKE /f "CcdPhysics.mak" CFG="CcdPhysics - Win32 Debug"
!MESSAGE
!MESSAGE Possible choices for configuration are:
!MESSAGE
!MESSAGE "CcdPhysics - Win32 Release" (based on "Win32 (x86) Static Library")
!MESSAGE "CcdPhysics - Win32 Debug" (based on "Win32 (x86) Static Library")
!MESSAGE
# Begin Project
# PROP AllowPerConfigDependencies 0
# PROP Scc_ProjName ""
# PROP Scc_LocalPath ""
CPP=cl.exe
RSC=rc.exe
!IF "$(CFG)" == "CcdPhysics - Win32 Release"
# PROP BASE Use_MFC 0
# PROP BASE Use_Debug_Libraries 0
# PROP BASE Output_Dir "CcdPhysics___Win32_Release"
# PROP BASE Intermediate_Dir "CcdPhysics___Win32_Release"
# PROP BASE Target_Dir ""
# PROP Use_MFC 0
# PROP Use_Debug_Libraries 0
# PROP Output_Dir "CcdPhysics___Win32_Release"
# PROP Intermediate_Dir "CcdPhysics___Win32_Release"
# PROP Target_Dir ""
LINK32=link.exe -lib
MTL=midl.exe
# ADD BASE CPP /nologo /W3 /GX /O2 /D "WIN32" /D "NDEBUG" /D "_MBCS" /D "_LIB" /YX /FD /c
# ADD CPP /nologo /W3 /GX /O2 /I "..\..\..\Bullet" /I "..\..\..\LinearMath" /I "..\..\..\BulletDynamics" /I "..\..\..\Extras\PhysicsInterface\Common" /I "..\..\..\Extras\PhysicsInterface\CcdPhysics" /D "WIN32" /D "NDEBUG" /D "_MBCS" /D "_LIB" /YX /FD /c
# ADD BASE RSC /l 0x809 /d "NDEBUG"
# ADD RSC /l 0x809 /d "NDEBUG"
BSC32=bscmake.exe
# ADD BASE BSC32 /nologo
# ADD BSC32 /nologo
LIB32=link.exe -lib
# ADD BASE LIB32 /nologo
# ADD LIB32 /nologo
!ELSEIF "$(CFG)" == "CcdPhysics - Win32 Debug"
# PROP BASE Use_MFC 0
# PROP BASE Use_Debug_Libraries 1
# PROP BASE Output_Dir "CcdPhysics___Win32_Debug"
# PROP BASE Intermediate_Dir "CcdPhysics___Win32_Debug"
# PROP BASE Target_Dir ""
# PROP Use_MFC 0
# PROP Use_Debug_Libraries 1
# PROP Output_Dir "CcdPhysics___Win32_Debug"
# PROP Intermediate_Dir "CcdPhysics___Win32_Debug"
# PROP Target_Dir ""
LINK32=link.exe -lib
MTL=midl.exe
# ADD BASE CPP /nologo /W3 /Gm /GX /ZI /Od /D "WIN32" /D "_DEBUG" /D "_MBCS" /D "_LIB" /YX /FD /GZ /c
# ADD CPP /nologo /W3 /Gm /GX /ZI /Od /I "..\..\..\Bullet" /I "..\..\..\LinearMath" /I "..\..\..\BulletDynamics" /I "..\..\..\Extras\PhysicsInterface\Common" /I "..\..\..\Extras\PhysicsInterface\CcdPhysics" /D "WIN32" /D "_DEBUG" /D "_MBCS" /D "_LIB" /YX /FD /GZ /c
# ADD BASE RSC /l 0x809 /d "_DEBUG"
# ADD RSC /l 0x809 /d "_DEBUG"
BSC32=bscmake.exe
# ADD BASE BSC32 /nologo
# ADD BSC32 /nologo
LIB32=link.exe -lib
# ADD BASE LIB32 /nologo
# ADD LIB32 /nologo
!ENDIF
# Begin Target
# Name "CcdPhysics - Win32 Release"
# Name "CcdPhysics - Win32 Debug"
# Begin Group "Source Files"
# PROP Default_Filter "cpp;c;cxx;rc;def;r;odl;idl;hpj;bat"
# Begin Source File
SOURCE=.\CcdPhysicsController.cpp
# End Source File
# Begin Source File
SOURCE=.\CcdPhysicsEnvironment.cpp
# End Source File
# End Group
# Begin Group "Header Files"
# PROP Default_Filter "h;hpp;hxx;hm;inl"
# Begin Source File
SOURCE=.\CcdPhysicsController.h
# End Source File
# Begin Source File
SOURCE=.\CcdPhysicsEnvironment.h
# End Source File
# End Group
# End Target
# End Project

View File

@@ -1,587 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "CcdPhysicsController.h"
#include "BulletDynamics/Dynamics/btRigidBody.h"
#include "PHY_IMotionState.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "BulletCollision/CollisionShapes/btConvexShape.h"
#include "CcdPhysicsEnvironment.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 btRigidBody class
//'temporarily' global variables
extern float gDeactivationTime;
extern bool gDisableDeactivation;
extern float gLinearSleepingTreshold;
extern float gAngularSleepingTreshold;
#include "BulletDynamics/Dynamics/btMassProps.h"
btVector3 startVel(0,0,0);//-10000);
CcdPhysicsController::CcdPhysicsController (const btCcdConstructionInfo& ci)
:m_cci(ci)
{
m_collisionDelay = 0;
m_newClientInfo = 0;
m_MotionState = ci.m_MotionState;
CreateRigidbody();
#ifdef WIN32
if (m_body->getInvMass())
m_body->setLinearVelocity(startVel);
#endif
}
btTransform CcdPhysicsController::GetTransformFromMotionState(PHY_IMotionState* motionState)
{
btTransform trans;
float tmp[3];
motionState->getWorldPosition(tmp[0],tmp[1],tmp[2]);
trans.setOrigin(btVector3(tmp[0],tmp[1],tmp[2]));
btQuaternion orn;
motionState->getWorldOrientation(orn[0],orn[1],orn[2],orn[3]);
trans.setRotation(orn);
return trans;
}
void CcdPhysicsController::CreateRigidbody()
{
btTransform trans = GetTransformFromMotionState(m_cci.m_MotionState);
btMassProps mp(m_cci.m_mass, m_cci.m_localInertiaTensor);
m_body = new btRigidBody(mp,0,0,m_cci.m_friction,m_cci.m_restitution);
m_body->m_collisionShape = m_cci.m_collisionShape;
//
// 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;
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
if (m_cci.m_physicsEnv)
m_cci.m_physicsEnv->removeCcdPhysicsController(this);
///this should not be deleted, it has been allocated by the user//delete m_MotionState;
delete m_body;
}
/**
SynchronizeMotionStates ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
*/
bool CcdPhysicsController::SynchronizeMotionStates(float time)
{
//sync non-static to motionstate, and static from motionstate (todo: add kinematic etc.)
if (!m_body->IsStatic())
{
const btVector3& worldPos = m_body->getCenterOfMassPosition();
m_MotionState->setWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
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]);
btVector3 scaling(scale[0],scale[1],scale[2]);
getCollisionShape()->setLocalScaling(scaling);
} else
{
btVector3 worldPos;
btQuaternion worldquat;
m_MotionState->getWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
m_MotionState->getWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
btTransform oldTrans = m_body->getCenterOfMassTransform();
btTransform newTrans(worldquat,worldPos);
m_body->setCenterOfMassTransform(newTrans);
//need to keep track of previous position for friction effects...
m_MotionState->calculateWorldTransformations();
float scale[3];
m_MotionState->getWorldScaling(scale[0],scale[1],scale[2]);
btVector3 scaling(scale[0],scale[1],scale[2]);
getCollisionShape()->setLocalScaling(scaling);
}
return true;
}
/**
WriteMotionStateToDynamics synchronizes dynas, kinematic and deformable entities (and do 'late binding')
*/
void CcdPhysicsController::WriteMotionStateToDynamics(bool nondynaonly)
{
}
void CcdPhysicsController::WriteDynamicsToMotionState()
{
}
// controller replication
void CcdPhysicsController::PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl)
{
m_MotionState = motionstate;
m_body = 0;
CreateRigidbody();
m_cci.m_physicsEnv->addCcdPhysicsController(this);
/* SM_Object* dynaparent=0;
SumoPhysicsController* sumoparentctrl = (SumoPhysicsController* )parentctrl;
if (sumoparentctrl)
{
dynaparent = sumoparentctrl->GetSumoObject();
}
SM_Object* orgsumoobject = m_sumoObj;
m_sumoObj = new SM_Object(
orgsumoobject->getShapeHandle(),
orgsumoobject->getMaterialProps(),
orgsumoobject->getShapeProps(),
dynaparent);
m_sumoObj->setRigidBody(orgsumoobject->isRigidBody());
m_sumoObj->setMargin(orgsumoobject->getMargin());
m_sumoObj->setPosition(orgsumoobject->getPosition());
m_sumoObj->setOrientation(orgsumoobject->getOrientation());
//if it is a dyna, register for a callback
m_sumoObj->registerCallback(*this);
m_sumoScene->add(* (m_sumoObj));
*/
}
// kinematic methods
void CcdPhysicsController::RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local)
{
if (m_body)
{
m_body->activate();
btVector3 dloc(dlocX,dlocY,dlocZ);
btTransform xform = m_body->getCenterOfMassTransform();
if (local)
{
dloc = xform.getBasis()*dloc;
}
xform.setOrigin(xform.getOrigin() + dloc);
m_body->setCenterOfMassTransform(xform);
}
}
void CcdPhysicsController::RelativeRotate(const float rotval[9],bool local)
{
if (m_body )
{
m_body->activate();
btMatrix3x3 drotmat( rotval[0],rotval[1],rotval[2],
rotval[4],rotval[5],rotval[6],
rotval[8],rotval[9],rotval[10]);
btMatrix3x3 currentOrn;
GetWorldOrientation(currentOrn);
btTransform xform = m_body->getCenterOfMassTransform();
xform.setBasis(xform.getBasis()*(local ?
drotmat : (currentOrn.inverse() * drotmat * currentOrn)));
m_body->setCenterOfMassTransform(xform);
}
}
void CcdPhysicsController::GetWorldOrientation(btMatrix3x3& mat)
{
float orn[4];
m_MotionState->getWorldOrientation(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)
{
btQuaternion q = m_body->getCenterOfMassTransform().getRotation();
quatImag0 = q[0];
quatImag1 = q[1];
quatImag2 = q[2];
quatReal = q[3];
}
void CcdPhysicsController::setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal)
{
m_body->activate();
m_MotionState->setWorldOrientation(quatImag0,quatImag1,quatImag2,quatReal);
btTransform xform = m_body->getCenterOfMassTransform();
xform.setRotation(btQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
m_body->setCenterOfMassTransform(xform);
}
void CcdPhysicsController::setPosition(float posX,float posY,float posZ)
{
m_body->activate();
m_MotionState->setWorldPosition(posX,posY,posZ);
btTransform xform = m_body->getCenterOfMassTransform();
xform.setOrigin(btVector3(posX,posY,posZ));
m_body->setCenterOfMassTransform(xform);
}
void CcdPhysicsController::resolveCombinedVelocities(float linvelX,float linvelY,float linvelZ,float angVelX,float angVelY,float angVelZ)
{
}
void CcdPhysicsController::getPosition(PHY__Vector3& pos) const
{
const btTransform& xform = m_body->getCenterOfMassTransform();
pos[0] = xform.getOrigin().x();
pos[1] = xform.getOrigin().y();
pos[2] = xform.getOrigin().z();
}
void CcdPhysicsController::setScaling(float scaleX,float scaleY,float 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 = btVector3(scaleX,scaleY,scaleZ);
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->setMassProps(m_cci.m_mass, m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
}
}
}
// physics methods
void CcdPhysicsController::ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local)
{
btVector3 torque(torqueX,torqueY,torqueZ);
btTransform xform = m_body->getCenterOfMassTransform();
if (local)
{
torque = xform.getBasis()*torque;
}
m_body->applyTorque(torque);
}
void CcdPhysicsController::ApplyForce(float forceX,float forceY,float forceZ,bool local)
{
btVector3 force(forceX,forceY,forceZ);
btTransform xform = m_body->getCenterOfMassTransform();
if (local)
{
force = xform.getBasis()*force;
}
m_body->applyCentralForce(force);
}
void CcdPhysicsController::SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local)
{
btVector3 angvel(ang_velX,ang_velY,ang_velZ);
if (angvel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
{
m_body->activate();
}
{
btTransform xform = m_body->getCenterOfMassTransform();
if (local)
{
angvel = xform.getBasis()*angvel;
}
m_body->setAngularVelocity(angvel);
}
}
void CcdPhysicsController::SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local)
{
btVector3 linVel(lin_velX,lin_velY,lin_velZ);
if (linVel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
{
m_body->activate();
}
{
btTransform xform = m_body->getCenterOfMassTransform();
if (local)
{
linVel = xform.getBasis()*linVel;
}
m_body->setLinearVelocity(linVel);
}
}
void CcdPhysicsController::applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ)
{
btVector3 impulse(impulseX,impulseY,impulseZ);
if (impulse.length2() > (SIMD_EPSILON*SIMD_EPSILON))
{
m_body->activate();
btVector3 pos(attachX,attachY,attachZ);
m_body->activate();
m_body->applyImpulse(impulse,pos);
}
}
void CcdPhysicsController::SetActive(bool active)
{
}
// reading out information from physics
void CcdPhysicsController::GetLinearVelocity(float& linvX,float& linvY,float& linvZ)
{
const btVector3& linvel = this->m_body->getLinearVelocity();
linvX = linvel.x();
linvY = linvel.y();
linvZ = linvel.z();
}
void CcdPhysicsController::GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ)
{
const btVector3& angvel= m_body->getAngularVelocity();
angVelX = angvel.x();
angVelY = angvel.y();
angVelZ = angvel.z();
}
void CcdPhysicsController::GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ)
{
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();
}
void CcdPhysicsController::getReactionForce(float& forceX,float& forceY,float& forceZ)
{
}
// dyna's that are rigidbody are free in orientation, dyna's with non-rigidbody are restricted
void CcdPhysicsController::setRigidBody(bool rigid)
{
if (!rigid)
{
//fake it for now
btVector3 inertia = m_body->getInvInertiaDiagLocal();
inertia[1] = 0.f;
m_body->setInvInertiaDiagLocal(inertia);
m_body->updateInertiaTensor();
}
}
// clientinfo for raycasts for example
void* CcdPhysicsController::getNewClientInfo()
{
return m_newClientInfo;
}
void CcdPhysicsController::setNewClientInfo(void* clientinfo)
{
m_newClientInfo = 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);
}
}
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;
}
PHY_IPhysicsController* CcdPhysicsController::GetReplica()
{
//very experimental, shape sharing is not implemented yet.
//just support btSphereShape/ConeShape for now
btCcdConstructionInfo cinfo = m_cci;
if (cinfo.m_collisionShape)
{
switch (cinfo.m_collisionShape->getShapeType())
{
case SPHERE_SHAPE_PROXYTYPE:
{
btSphereShape* orgShape = (btSphereShape*)cinfo.m_collisionShape;
cinfo.m_collisionShape = new btSphereShape(*orgShape);
break;
}
case CONE_SHAPE_PROXYTYPE:
{
btConeShape* orgShape = (btConeShape*)cinfo.m_collisionShape;
cinfo.m_collisionShape = new btConeShape(*orgShape);
break;
}
default:
{
return 0;
}
}
}
cinfo.m_MotionState = new DefaultMotionState();
CcdPhysicsController* replica = new CcdPhysicsController(cinfo);
return replica;
}
///////////////////////////////////////////////////////////
///A small utility class, DefaultMotionState
///
///////////////////////////////////////////////////////////
DefaultMotionState::DefaultMotionState()
{
m_worldTransform.setIdentity();
m_localScaling.setValue(1.f,1.f,1.f);
}
DefaultMotionState::~DefaultMotionState()
{
}
void DefaultMotionState::getWorldPosition(float& posX,float& posY,float& posZ)
{
posX = m_worldTransform.getOrigin().x();
posY = m_worldTransform.getOrigin().y();
posZ = m_worldTransform.getOrigin().z();
}
void DefaultMotionState::getWorldScaling(float& scaleX,float& scaleY,float& scaleZ)
{
scaleX = m_localScaling.getX();
scaleY = m_localScaling.getY();
scaleZ = m_localScaling.getZ();
}
void DefaultMotionState::getWorldOrientation(float& quatIma0,float& quatIma1,float& quatIma2,float& quatReal)
{
quatIma0 = m_worldTransform.getRotation().x();
quatIma1 = m_worldTransform.getRotation().y();
quatIma2 = m_worldTransform.getRotation().z();
quatReal = m_worldTransform.getRotation()[3];
}
void DefaultMotionState::setWorldPosition(float posX,float posY,float posZ)
{
btPoint3 pos(posX,posY,posZ);
m_worldTransform.setOrigin( pos );
}
void DefaultMotionState::setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal)
{
btQuaternion orn(quatIma0,quatIma1,quatIma2,quatReal);
m_worldTransform.setRotation( orn );
}
void DefaultMotionState::calculateWorldTransformations()
{
}

View File

@@ -1,254 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BULLET2_PHYSICSCONTROLLER_H
#define BULLET2_PHYSICSCONTROLLER_H
#include "PHY_IPhysicsController.h"
/// PHY_IPhysicsController is the abstract simplified Interface to a physical object.
/// It contains the IMotionState and IDeformableMesh Interfaces.
#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 btCollisionShape access
class btCollisionShape;
extern float gDeactivationTime;
extern float gLinearSleepingTreshold;
extern float gAngularSleepingTreshold;
extern bool gDisableDeactivation;
class CcdPhysicsEnvironment;
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 btCollisionDispatcher::needsCollision
enum CollisionFilterGroups
{
DefaultFilter = 1,
StaticFilter = 2,
KinematicFilter = 4,
DebrisFilter = 8,
AllFilter = DefaultFilter | StaticFilter | KinematicFilter | DebrisFilter,
};
btCcdConstructionInfo()
: m_gravity(0,0,0),
m_scaling(1.f,1.f,1.f),
m_mass(0.f),
m_restitution(0.1f),
m_friction(0.5f),
m_linearDamping(0.1f),
m_angularDamping(0.1f),
m_collisionFlags(0),
m_collisionFilterGroup(DefaultFilter),
m_collisionFilterMask(AllFilter),
m_MotionState(0),
m_physicsEnv(0),
m_inertiaFactor(1.f)
{
}
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 btCollisionDispatcher::needsCollision and needsResponse
///both values default to 1
short int m_collisionFilterGroup;
short int m_collisionFilterMask;
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 btRigidBody;
///CcdPhysicsController is a physics object that supports continuous collision detection and time of impact based physics resolution.
class CcdPhysicsController : public PHY_IPhysicsController
{
btRigidBody* m_body;
class PHY_IMotionState* m_MotionState;
void* m_newClientInfo;
btCcdConstructionInfo m_cci;//needed for replication
void GetWorldOrientation(btMatrix3x3& mat);
void CreateRigidbody();
public:
int m_collisionDelay;
CcdPhysicsController (const btCcdConstructionInfo& ci);
virtual ~CcdPhysicsController();
btRigidBody* getRigidBody() { return m_body;}
btCollisionShape* getCollisionShape() {
return m_body->getCollisionShape();
}
////////////////////////////////////
// PHY_IPhysicsController interface
////////////////////////////////////
/**
SynchronizeMotionStates ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
*/
virtual bool SynchronizeMotionStates(float time);
/**
WriteMotionStateToDynamics ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
*/
virtual void WriteMotionStateToDynamics(bool nondynaonly);
virtual void WriteDynamicsToMotionState();
// controller replication
virtual void PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl);
// kinematic methods
virtual void RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local);
virtual void RelativeRotate(const float drot[9],bool local);
virtual void getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal);
virtual void setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal);
virtual void setPosition(float posX,float posY,float posZ);
virtual void getPosition(PHY__Vector3& pos) const;
virtual void setScaling(float scaleX,float scaleY,float scaleZ);
// physics methods
virtual void ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local);
virtual void ApplyForce(float forceX,float forceY,float forceZ,bool local);
virtual void SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local);
virtual void SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local);
virtual void applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ);
virtual void SetActive(bool active);
// reading out information from physics
virtual void GetLinearVelocity(float& linvX,float& linvY,float& linvZ);
virtual void GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ);
virtual void GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ);
virtual void getReactionForce(float& forceX,float& forceY,float& forceZ);
// dyna's that are rigidbody are free in orientation, dyna's with non-rigidbody are restricted
virtual void setRigidBody(bool rigid);
virtual void resolveCombinedVelocities(float linvelX,float linvelY,float linvelZ,float angVelX,float angVelY,float angVelZ);
// clientinfo for raycasts for example
virtual void* getNewClientInfo();
virtual void setNewClientInfo(void* clientinfo);
virtual PHY_IPhysicsController* GetReplica();
///There should be no 'SetCollisionFilterGroup' method, as changing this during run-time is will result in errors
short int GetCollisionFilterGroup() const
{
return m_cci.m_collisionFilterGroup;
}
///There should be no 'SetCollisionFilterGroup' method, as changing this during run-time is will result in errors
short int GetCollisionFilterMask() const
{
return m_cci.m_collisionFilterMask;
}
virtual void calcXform() {} ;
virtual void setMargin(float margin) {};
virtual float getMargin() const {return 0.f;};
bool wantsSleeping();
void UpdateDeactivation(float timeStep);
static btTransform GetTransformFromMotionState(PHY_IMotionState* motionState);
void setAabb(const btVector3& aabbMin,const btVector3& aabbMax);
class PHY_IMotionState* GetMotionState()
{
return m_MotionState;
}
const class PHY_IMotionState* GetMotionState() const
{
return m_MotionState;
}
};
///DefaultMotionState implements standard motionstate, using btTransform
class DefaultMotionState : public PHY_IMotionState
{
public:
DefaultMotionState();
virtual ~DefaultMotionState();
virtual void getWorldPosition(float& posX,float& posY,float& posZ);
virtual void getWorldScaling(float& scaleX,float& scaleY,float& scaleZ);
virtual void getWorldOrientation(float& quatIma0,float& quatIma1,float& quatIma2,float& quatReal);
virtual void setWorldPosition(float posX,float posY,float posZ);
virtual void setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal);
virtual void calculateWorldTransformations();
btTransform m_worldTransform;
btVector3 m_localScaling;
};
#endif //BULLET2_PHYSICSCONTROLLER_H

File diff suppressed because it is too large Load Diff

View File

@@ -1,267 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef CCDPHYSICSENVIRONMENT
#define CCDPHYSICSENVIRONMENT
#include "PHY_IPhysicsEnvironment.h"
#include <vector>
class CcdPhysicsController;
#include "LinearMath/btVector3.h"
#include "LinearMath/btTransform.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 "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
class WrapperVehicle;
class btPersistentManifold;
class btBroadphaseInterface;
class btOverlappingPairCache;
class btIDebugDraw;
class PHY_IVehicle;
/// 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
{
btVector3 m_gravity;
protected:
btIDebugDraw* m_debugDrawer;
//solver iterations
int m_numIterations;
//timestep subdivisions
int m_numTimeSubSteps;
int m_ccdMode;
int m_solverType;
int m_profileTimings;
bool m_enableSatCollisionDetection;
btContactSolverInfo m_solverInfo;
btSimulationIslandManager* m_islandManager;
public:
CcdPhysicsEnvironment(btDispatcher* dispatcher=0, btOverlappingPairCache* pairCache=0);
virtual ~CcdPhysicsEnvironment();
/////////////////////////////////////
//PHY_IPhysicsEnvironment interface
/////////////////////////////////////
/// Perform an integration step of duration 'timeStep'.
virtual void setDebugDrawer(btIDebugDraw* debugDrawer)
{
m_debugDrawer = debugDrawer;
}
virtual void setNumIterations(int numIter);
virtual void setNumTimeSubSteps(int numTimeSubSteps)
{
m_numTimeSubSteps = numTimeSubSteps;
}
virtual void setDeactivationTime(float dTime);
virtual void setDeactivationLinearTreshold(float linTresh) ;
virtual void setDeactivationAngularTreshold(float angTresh) ;
virtual void setContactBreakingTreshold(float contactBreakingTreshold) ;
virtual void setCcdMode(int ccdMode);
virtual void setSolverType(int solverType);
virtual void setSolverSorConstant(float sor);
virtual void setSolverTau(float tau);
virtual void setSolverDamping(float damping);
virtual void setLinearAirDamping(float damping);
virtual void setUseEpa(bool epa) ;
virtual void beginFrame();
virtual void endFrame() {};
/// Perform an integration step of duration 'timeStep'.
virtual bool proceedDeltaTime(double curTime,float timeStep);
virtual bool proceedDeltaTimeOneStep(float timeStep);
virtual void setFixedTimeStep(bool useFixedTimeStep,float fixedTimeStep){};
//returns 0.f if no fixed timestep is used
virtual float getFixedTimeStep(){ return 0.f;};
virtual void setDebugMode(int debugMode);
virtual void setGravity(float x,float y,float z);
virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type,
float pivotX,float pivotY,float pivotZ,
float axisX,float axisY,float axisZ);
//Following the COLLADA physics specification for constraints
virtual int createUniversalD6Constraint(
class PHY_IPhysicsController* ctrlRef,class PHY_IPhysicsController* ctrlOther,
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();
#ifdef NEW_BULLET_VEHICLE_SUPPORT
//complex constraint for vehicles
virtual PHY_IVehicle* getVehicleConstraint(int constraintId);
#else
virtual class PHY_IVehicle* getVehicleConstraint(int constraintId)
{
return 0;
}
#endif //NEW_BULLET_VEHICLE_SUPPORT
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);
//Methods for gamelogic collision/physics callbacks
virtual void addSensor(PHY_IPhysicsController* ctrl);
virtual void removeSensor(PHY_IPhysicsController* ctrl);
virtual void addTouchCallback(int response_class, PHY_ResponseCallback callback, void *user);
virtual void requestCollisionCallback(PHY_IPhysicsController* ctrl);
virtual void removeCollisionCallback(PHY_IPhysicsController* ctrl);
virtual PHY_IPhysicsController* CreateSphereController(float radius,const PHY__Vector3& position);
virtual PHY_IPhysicsController* CreateConeController(float coneradius,float coneheight);
virtual int getNumContactPoints();
virtual void getContactPoint(int i,float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ);
//////////////////////
//CcdPhysicsEnvironment interface
////////////////////////
void addCcdPhysicsController(CcdPhysicsController* ctrl);
void removeCcdPhysicsController(CcdPhysicsController* ctrl);
btBroadphaseInterface* getBroadphase();
bool IsSatCollisionDetectionEnabled() const
{
return m_enableSatCollisionDetection;
}
void EnableSatCollisionDetection(bool enableSat)
{
m_enableSatCollisionDetection = enableSat;
}
void UpdateAabbs(float timeStep);
int GetNumControllers();
CcdPhysicsController* GetPhysicsController( int index);
const btPersistentManifold* getManifold(int index) const;
std::vector<btTypedConstraint*> m_constraints;
void SyncMotionStates(float timeStep);
class btCollisionWorld* getCollisionWorld()
{
return m_collisionWorld;
}
const class btCollisionWorld* getCollisionWorld() const
{
return m_collisionWorld;
}
btSimulationIslandManager* getSimulationIslandManager()
{
return m_islandManager;
}
const btSimulationIslandManager* getSimulationIslandManager() const
{
return m_islandManager;
}
class btConstraintSolver* GetConstraintSolver()
{
return m_solver;
}
protected:
std::vector<CcdPhysicsController*> m_controllers;
std::vector<CcdPhysicsController*> m_triggerControllers;
PHY_ResponseCallback m_triggerCallbacks[PHY_NUM_RESPONSE];
void* m_triggerCallbacksUserPtrs[PHY_NUM_RESPONSE];
std::vector<WrapperVehicle*> m_wrapperVehicles;
class btCollisionWorld* m_collisionWorld;
class btConstraintSolver* m_solver;
bool m_scalingPropagated;
};
#endif //CCDPHYSICSENVIRONMENT

View File

@@ -1,131 +0,0 @@
<?xml version="1.0" encoding="Windows-1252"?>
<VisualStudioProject
ProjectType="Visual C++"
Version="7.10"
Name="CcdPhysics"
ProjectGUID="{E3D57F36-36AC-4E9A-B0E0-2AE4510FCBFE}"
Keyword="Win32Proj">
<Platforms>
<Platform
Name="Win32"/>
</Platforms>
<Configurations>
<Configuration
Name="Debug|Win32"
OutputDirectory="Debug"
IntermediateDirectory="Debug"
ConfigurationType="4"
CharacterSet="2">
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories="..\Common;..\..\..\LinearMath;..\..\..\Bullet;..\..\..\BulletDynamics"
PreprocessorDefinitions="WIN32;_DEBUG;_LIB"
MinimalRebuild="TRUE"
BasicRuntimeChecks="3"
RuntimeLibrary="3"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="TRUE"
DebugInformationFormat="4"/>
<Tool
Name="VCCustomBuildTool"/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/CcdPhysics.lib"/>
<Tool
Name="VCMIDLTool"/>
<Tool
Name="VCPostBuildEventTool"/>
<Tool
Name="VCPreBuildEventTool"/>
<Tool
Name="VCPreLinkEventTool"/>
<Tool
Name="VCResourceCompilerTool"/>
<Tool
Name="VCWebServiceProxyGeneratorTool"/>
<Tool
Name="VCXMLDataGeneratorTool"/>
<Tool
Name="VCManagedWrapperGeneratorTool"/>
<Tool
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
</Configuration>
<Configuration
Name="Release|Win32"
OutputDirectory="Release"
IntermediateDirectory="Release"
ConfigurationType="4"
CharacterSet="2">
<Tool
Name="VCCLCompilerTool"
AdditionalIncludeDirectories="..\Common;..\..\..\LinearMath;..\..\..\Bullet;..\..\..\BulletDynamics"
PreprocessorDefinitions="WIN32;NDEBUG;_LIB"
RuntimeLibrary="4"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="TRUE"
DebugInformationFormat="3"/>
<Tool
Name="VCCustomBuildTool"/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/CcdPhysics.lib"/>
<Tool
Name="VCMIDLTool"/>
<Tool
Name="VCPostBuildEventTool"/>
<Tool
Name="VCPreBuildEventTool"/>
<Tool
Name="VCPreLinkEventTool"/>
<Tool
Name="VCResourceCompilerTool"/>
<Tool
Name="VCWebServiceProxyGeneratorTool"/>
<Tool
Name="VCXMLDataGeneratorTool"/>
<Tool
Name="VCManagedWrapperGeneratorTool"/>
<Tool
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
</Configuration>
</Configurations>
<References>
</References>
<Files>
<Filter
Name="Source Files"
Filter="cpp;c;cxx;def;odl;idl;hpj;bat;asm;asmx"
UniqueIdentifier="{4FC737F1-C7A5-4376-A066-2A32D752A2FF}">
<File
RelativePath=".\CcdPhysicsController.cpp">
</File>
<File
RelativePath=".\CcdPhysicsEnvironment.cpp">
</File>
</Filter>
<Filter
Name="Header Files"
Filter="h;hpp;hxx;hm;inl;inc;xsd"
UniqueIdentifier="{93995380-89BD-4b04-88EB-625FBE52EBFB}">
<File
RelativePath=".\CcdPhysicsController.h">
</File>
<File
RelativePath=".\CcdPhysicsEnvironment.h">
</File>
</Filter>
<Filter
Name="Resource Files"
Filter="rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx"
UniqueIdentifier="{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}">
</Filter>
<File
RelativePath=".\ReadMe.txt">
</File>
</Files>
<Globals>
</Globals>
</VisualStudioProject>

View File

@@ -1,191 +0,0 @@
<?xml version="1.0" encoding="Windows-1252"?>
<VisualStudioProject
ProjectType="Visual C++"
Version="8.00"
Name="CcdPhysics"
ProjectGUID="{E3D57F36-36AC-4E9A-B0E0-2AE4510FCBFE}"
Keyword="Win32Proj"
>
<Platforms>
<Platform
Name="Win32"
/>
</Platforms>
<ToolFiles>
</ToolFiles>
<Configurations>
<Configuration
Name="Debug|Win32"
OutputDirectory="Debug"
IntermediateDirectory="Debug"
ConfigurationType="4"
CharacterSet="2"
>
<Tool
Name="VCPreBuildEventTool"
/>
<Tool
Name="VCCustomBuildTool"
/>
<Tool
Name="VCXMLDataGeneratorTool"
/>
<Tool
Name="VCWebServiceProxyGeneratorTool"
/>
<Tool
Name="VCMIDLTool"
/>
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories="..\Common;..\..\..\LinearMath;..\..\..\Bullet;..\..\..\BulletDynamics"
PreprocessorDefinitions="WIN32;_DEBUG;_LIB"
MinimalRebuild="true"
BasicRuntimeChecks="3"
RuntimeLibrary="1"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="true"
DebugInformationFormat="4"
/>
<Tool
Name="VCManagedResourceCompilerTool"
/>
<Tool
Name="VCResourceCompilerTool"
/>
<Tool
Name="VCPreLinkEventTool"
/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/CcdPhysics.lib"
/>
<Tool
Name="VCALinkTool"
/>
<Tool
Name="VCXDCMakeTool"
/>
<Tool
Name="VCBscMakeTool"
/>
<Tool
Name="VCFxCopTool"
/>
<Tool
Name="VCPostBuildEventTool"
/>
</Configuration>
<Configuration
Name="Release|Win32"
OutputDirectory="Release"
IntermediateDirectory="Release"
ConfigurationType="4"
CharacterSet="2"
>
<Tool
Name="VCPreBuildEventTool"
/>
<Tool
Name="VCCustomBuildTool"
/>
<Tool
Name="VCXMLDataGeneratorTool"
/>
<Tool
Name="VCWebServiceProxyGeneratorTool"
/>
<Tool
Name="VCMIDLTool"
/>
<Tool
Name="VCCLCompilerTool"
AdditionalIncludeDirectories="..\Common;..\..\..\LinearMath;..\..\..\Bullet;..\..\..\BulletDynamics"
PreprocessorDefinitions="WIN32;NDEBUG;_LIB"
RuntimeLibrary="0"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="true"
DebugInformationFormat="3"
/>
<Tool
Name="VCManagedResourceCompilerTool"
/>
<Tool
Name="VCResourceCompilerTool"
/>
<Tool
Name="VCPreLinkEventTool"
/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/CcdPhysics.lib"
/>
<Tool
Name="VCALinkTool"
/>
<Tool
Name="VCXDCMakeTool"
/>
<Tool
Name="VCBscMakeTool"
/>
<Tool
Name="VCFxCopTool"
/>
<Tool
Name="VCPostBuildEventTool"
/>
</Configuration>
</Configurations>
<References>
</References>
<Files>
<Filter
Name="Source Files"
Filter="cpp;c;cxx;def;odl;idl;hpj;bat;asm;asmx"
UniqueIdentifier="{4FC737F1-C7A5-4376-A066-2A32D752A2FF}"
>
<File
RelativePath=".\CcdPhysicsController.cpp"
>
</File>
<File
RelativePath=".\CcdPhysicsEnvironment.cpp"
>
</File>
</Filter>
<Filter
Name="Header Files"
Filter="h;hpp;hxx;hm;inl;inc;xsd"
UniqueIdentifier="{93995380-89BD-4b04-88EB-625FBE52EBFB}"
>
<File
RelativePath=".\CcdPhysicsController.h"
>
</File>
<File
RelativePath=".\CcdPhysicsEnvironment.h"
>
</File>
</Filter>
<Filter
Name="Resource Files"
Filter="rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx"
UniqueIdentifier="{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}"
>
</Filter>
<File
RelativePath=".\VTune\CcdPhysics.vpj"
>
</File>
<File
RelativePath=".\ReadMe.txt"
>
</File>
</Files>
<Globals>
</Globals>
</VisualStudioProject>

View File

@@ -1,10 +0,0 @@
SubDir TOP Extras PhysicsInterface CcdPhysics ;
IncludeDir Extras/PhysicsInterface/Common ;
Library bulletccdphysics : [ Wildcard *.h *.cpp ] ;
CFlags bulletccdphysics : [ FIncludes $(TOP)/Extras/PhysicsInterface/Common ] ;
LibDepends bulletccdphysics : bulletcollision bulletphysicsinterfacecommon bulletdynamics ;
InstallHeader [ Wildcard *.h ] : CcdPhysics ;

View File

@@ -1,350 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "ParallelIslandDispatcher.h"
#include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h"
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include <algorithm>
static int gNumManifold2 = 0;
ParallelIslandDispatcher::ParallelIslandDispatcher ():
m_useIslands(true),
m_defaultManifoldResult(0,0,0),
m_count(0)
{
int i;
for (i=0;i<MAX_BROADPHASE_COLLISION_TYPES;i++)
{
for (int j=0;j<MAX_BROADPHASE_COLLISION_TYPES;j++)
{
m_doubleDispatch[i][j] = 0;
}
}
};
btPersistentManifold* ParallelIslandDispatcher::getNewManifold(void* b0,void* b1)
{
gNumManifold2++;
//ASSERT(gNumManifold < 65535);
btCollisionObject* body0 = (btCollisionObject*)b0;
btCollisionObject* body1 = (btCollisionObject*)b1;
btPersistentManifold* manifold = new btPersistentManifold (body0,body1);
m_manifoldsPtr.push_back(manifold);
return manifold;
}
void ParallelIslandDispatcher::clearManifold(btPersistentManifold* manifold)
{
manifold->clearManifold();
}
void ParallelIslandDispatcher::releaseManifold(btPersistentManifold* manifold)
{
gNumManifold2--;
//printf("releaseManifold: gNumManifold2 %d\n",gNumManifold2);
clearManifold(manifold);
std::vector<btPersistentManifold*>::iterator i =
std::find(m_manifoldsPtr.begin(), m_manifoldsPtr.end(), manifold);
if (!(i == m_manifoldsPtr.end()))
{
std::swap(*i, m_manifoldsPtr.back());
m_manifoldsPtr.pop_back();
delete manifold;
}
}
//
// todo: this is random access, it can be walked 'cache friendly'!
//
void ParallelIslandDispatcher::buildAndProcessIslands(btCollisionObjectArray& collisionObjects, IslandCallback* callback)
{
int numBodies = collisionObjects.size();
for (int islandId=0;islandId<numBodies;islandId++)
{
std::vector<btPersistentManifold*> islandmanifold;
//int numSleeping = 0;
bool allSleeping = true;
int i;
for (i=0;i<numBodies;i++)
{
btCollisionObject* colObj0 = collisionObjects[i];
if (colObj0->m_islandTag1 == islandId)
{
if (colObj0->GetActivationState()== ACTIVE_TAG)
{
allSleeping = false;
}
if (colObj0->GetActivationState()== DISABLE_DEACTIVATION)
{
allSleeping = false;
}
}
}
for (i=0;i<getNumManifolds();i++)
{
btPersistentManifold* manifold = this->getManifoldByIndexInternal(i);
//filtering for response
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)))
{
if (needsResponse(*colObj0,*colObj1))
islandmanifold.push_back(manifold);
}
}
}
if (allSleeping)
{
int i;
for (i=0;i<numBodies;i++)
{
btCollisionObject* colObj0 = collisionObjects[i];
if (colObj0->m_islandTag1 == islandId)
{
colObj0->SetActivationState( ISLAND_SLEEPING );
}
}
} else
{
int i;
for (i=0;i<numBodies;i++)
{
btCollisionObject* colObj0 = collisionObjects[i];
if (colObj0->m_islandTag1 == islandId)
{
if ( colObj0->GetActivationState() == ISLAND_SLEEPING)
{
colObj0->SetActivationState( WANTS_DEACTIVATION);
}
}
}
/// Process the actual simulation, only if not sleeping/deactivated
if (islandmanifold.size())
{
callback->ProcessIsland(&islandmanifold[0],islandmanifold.size());
}
}
}
}
btCollisionAlgorithm* ParallelIslandDispatcher::internalFindAlgorithm(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
{
m_count++;
btCollisionObject* body0 = (btCollisionObject*)proxy0.m_clientObject;
btCollisionObject* body1 = (btCollisionObject*)proxy1.m_clientObject;
btCollisionAlgorithmConstructionInfo ci;
ci.m_dispatcher = this;
if (body0->m_collisionShape->isConvex() && body1->m_collisionShape->isConvex() )
{
return new btConvexConvexAlgorithm(0,ci,&proxy0,&proxy1);
}
if (body0->m_collisionShape->isConvex() && body1->m_collisionShape->isConcave())
{
return new btConvexConcaveCollisionAlgorithm(ci,&proxy0,&proxy1);
}
if (body1->m_collisionShape->isConvex() && body0->m_collisionShape->isConcave())
{
return new btConvexConcaveCollisionAlgorithm(ci,&proxy1,&proxy0);
}
if (body0->m_collisionShape->isCompound())
{
return new btCompoundCollisionAlgorithm(ci,&proxy0,&proxy1);
} else
{
if (body1->m_collisionShape->isCompound())
{
return new btCompoundCollisionAlgorithm(ci,&proxy1,&proxy0);
}
}
//failed to find an algorithm
return new btEmptyAlgorithm(ci);
}
bool ParallelIslandDispatcher::needsResponse(const btCollisionObject& colObj0,const btCollisionObject& colObj1)
{
//here you can do filtering
bool hasResponse =
(!(colObj0.m_collisionFlags & btCollisionObject::noContactResponse)) &&
(!(colObj1.m_collisionFlags & btCollisionObject::noContactResponse));
hasResponse = hasResponse &&
(colObj0.IsActive() || colObj1.IsActive());
return hasResponse;
}
bool ParallelIslandDispatcher::needsCollision(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
{
btCollisionObject* body0 = (btCollisionObject*)proxy0.m_clientObject;
btCollisionObject* body1 = (btCollisionObject*)proxy1.m_clientObject;
assert(body0);
assert(body1);
bool needsCollision = true;
if ((body0->m_collisionFlags & btCollisionObject::isStatic) &&
(body1->m_collisionFlags & btCollisionObject::isStatic))
needsCollision = false;
if ((!body0->IsActive()) && (!body1->IsActive()))
needsCollision = false;
return needsCollision ;
}
///allows the user to get contact point callbacks
btManifoldResult* ParallelIslandDispatcher::getNewManifoldResult(btCollisionObject* obj0,btCollisionObject* obj1,btPersistentManifold* manifold)
{
//in-place, this prevents parallel dispatching, but just adding a list would fix that.
btManifoldResult* manifoldResult = new (&m_defaultManifoldResult) btManifoldResult(obj0,obj1,manifold);
return manifoldResult;
}
///allows the user to get contact point callbacks
void ParallelIslandDispatcher::releaseManifoldResult(btManifoldResult*)
{
}
void ParallelIslandDispatcher::dispatchAllCollisionPairs(btOverlappingPairCache* pairCache,btDispatcherInfo& dispatchInfo)
{
//m_blockedForChanges = true;
assert(0);
/*
int dispatcherId = getUniqueId();
int i;
for (i=0;i<numPairs;i++)
{
btBroadphasePair& pair = pairs[i];
if (dispatcherId>= 0)
{
//dispatcher will keep algorithms persistent in the collision pair
if (!pair.m_algorithms[dispatcherId])
{
pair.m_algorithms[dispatcherId] = findAlgorithm(
*pair.m_pProxy0,
*pair.m_pProxy1);
}
if (pair.m_algorithms[dispatcherId])
{
if (dispatchInfo.m_dispatchFunc == btDispatcherInfo::DISPATCH_DISCRETE)
{
pair.m_algorithms[dispatcherId]->processCollision(pair.m_pProxy0,pair.m_pProxy1,dispatchInfo);
} else
{
float toi = pair.m_algorithms[dispatcherId]->calculateTimeOfImpact(pair.m_pProxy0,pair.m_pProxy1,dispatchInfo);
if (dispatchInfo.m_timeOfImpact > toi)
dispatchInfo.m_timeOfImpact = toi;
}
}
} else
{
//non-persistent algorithm dispatcher
btCollisionAlgorithm* algo = findAlgorithm(
*pair.m_pProxy0,
*pair.m_pProxy1);
if (algo)
{
if (dispatchInfo.m_dispatchFunc == btDispatcherInfo::DISPATCH_DISCRETE)
{
algo->processCollision(pair.m_pProxy0,pair.m_pProxy1,dispatchInfo);
} else
{
float toi = algo->calculateTimeOfImpact(pair.m_pProxy0,pair.m_pProxy1,dispatchInfo);
if (dispatchInfo.m_timeOfImpact > toi)
dispatchInfo.m_timeOfImpact = toi;
}
}
}
}
*/
//m_blockedForChanges = false;
}

View File

@@ -1,128 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef PARALLEL_ISLAND_DISPATCHER_H
#define PARALLEL_ISLAND_DISPATCHER_H
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
#include "BulletCollision/CollisionDispatch/btUnionFind.h"
#include "BulletCollision/CollisionDispatch/btManifoldResult.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include <vector>
class btIDebugDraw;
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
///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 btDispatcher
{
std::vector<btPersistentManifold*> m_manifoldsPtr;
btUnionFind m_unionFind;
bool m_useIslands;
btManifoldResult m_defaultManifoldResult;
btCollisionAlgorithmCreateFunc* m_doubleDispatch[MAX_BROADPHASE_COLLISION_TYPES][MAX_BROADPHASE_COLLISION_TYPES];
public:
btUnionFind& getUnionFind() { return m_unionFind;}
struct IslandCallback
{
virtual ~IslandCallback() {};
virtual void ProcessIsland(btPersistentManifold** manifolds,int numManifolds) = 0;
};
int getNumManifolds() const
{
return m_manifoldsPtr.size();
}
btPersistentManifold* getManifoldByIndexInternal(int index)
{
return m_manifoldsPtr[index];
}
const btPersistentManifold* getManifoldByIndexInternal(int index) const
{
return m_manifoldsPtr[index];
}
void initUnionFind(int n)
{
if (m_useIslands)
m_unionFind.reset(n);
}
void findUnions();
int m_count;
ParallelIslandDispatcher ();
virtual ~ParallelIslandDispatcher() {};
virtual btPersistentManifold* getNewManifold(void* b0,void* b1);
virtual void releaseManifold(btPersistentManifold* manifold);
virtual void buildAndProcessIslands(btCollisionObjectArray& collisionObjects, IslandCallback* callback);
///allows the user to get contact point callbacks
virtual btManifoldResult* getNewManifoldResult(btCollisionObject* obj0,btCollisionObject* obj1,btPersistentManifold* manifold);
///allows the user to get contact point callbacks
virtual void releaseManifoldResult(btManifoldResult*);
virtual void clearManifold(btPersistentManifold* manifold);
btCollisionAlgorithm* findAlgorithm(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1)
{
btCollisionAlgorithm* algo = internalFindAlgorithm(proxy0,proxy1);
return algo;
}
btCollisionAlgorithm* internalFindAlgorithm(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1);
virtual bool needsCollision(btBroadphaseProxy& proxy0,btBroadphaseProxy& proxy1);
virtual bool needsResponse(const btCollisionObject& colObj0,const btCollisionObject& colObj1);
virtual int getUniqueId() { return RIGIDBODY_DISPATCHER;}
virtual void dispatchAllCollisionPairs(btOverlappingPairCache* pairCache,btDispatcherInfo& dispatchInfo);
};
#endif //PARALLEL_ISLAND_DISPATCHER_H

View File

@@ -1,206 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "ParallelPhysicsEnvironment.h"
#include "CcdPhysicsController.h"
#include "ParallelIslandDispatcher.h"
#include "BulletCollision/CollisionDispatch/btCollisionWorld.h"
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
#include "SimulationIsland.h"
ParallelPhysicsEnvironment::ParallelPhysicsEnvironment(ParallelIslandDispatcher* dispatcher, btOverlappingPairCache* pairCache):
CcdPhysicsEnvironment(dispatcher,pairCache)
{
}
ParallelPhysicsEnvironment::~ParallelPhysicsEnvironment()
{
}
/// Perform an integration step of duration 'timeStep'.
bool ParallelPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
{
// Make sure the broadphase / overlapping AABB paircache is up-to-date
btOverlappingPairCache* scene = m_collisionWorld->getPairCache();
scene->refreshOverlappingPairs();
// Find the connected sets that can be simulated in parallel
// Using union find
#ifdef USE_QUICKPROF
btProfiler::beginBlock("IslandUnionFind");
#endif //USE_QUICKPROF
getSimulationIslandManager()->updateActivationState(getCollisionWorld(),getCollisionWorld()->getDispatcher());
{
int i;
int numConstraints = m_constraints.size();
for (i=0;i< numConstraints ; i++ )
{
btTypedConstraint* constraint = m_constraints[i];
const btRigidBody* colObj0 = &constraint->getRigidBodyA();
const btRigidBody* colObj1 = &constraint->getRigidBodyB();
if (((colObj0) && ((colObj0)->mergesSimulationIslands())) &&
((colObj1) && ((colObj1)->mergesSimulationIslands())))
{
if (colObj0->IsActive() || colObj1->IsActive())
{
getSimulationIslandManager()->getUnionFind().unite((colObj0)->m_islandTag1,
(colObj1)->m_islandTag1);
}
}
}
}
//Store the island id in each body
getSimulationIslandManager()->storeIslandActivationState(getCollisionWorld());
#ifdef USE_QUICKPROF
btProfiler::endBlock("IslandUnionFind");
#endif //USE_QUICKPROF
///build simulation islands
#ifdef USE_QUICKPROF
btProfiler::beginBlock("BuildIslands");
#endif //USE_QUICKPROF
std::vector<SimulationIsland> simulationIslands;
simulationIslands.resize(GetNumControllers());
int k;
for (k=0;k<GetNumControllers();k++)
{
CcdPhysicsController* ctrl = m_controllers[k];
int tag = ctrl->getRigidBody()->m_islandTag1;
if (tag>=0)
{
simulationIslands[tag].m_controllers.push_back(ctrl);
}
}
btDispatcher* dispatcher = getCollisionWorld()->getDispatcher();
//this is a brute force approach, will rethink later about more subtle ways
int i;
assert(0);
/*
for (i=0;i< scene->GetNumOverlappingPairs();i++)
{
btBroadphasePair* pair = &scene->GetOverlappingPair(i);
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)
{
simulationIslands[col0->m_islandTag1].m_overlappingPairIndices.push_back(i);
} else
{
simulationIslands[col1->m_islandTag1].m_overlappingPairIndices.push_back(i);
}
}
*/
//store constraint indices for each island
for (unsigned int ui=0;ui<m_constraints.size();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);
} else
{
simulationIslands[constraint.getRigidBodyB().m_islandTag1].m_constraintIndices.push_back(ui);
}
}
//add all overlapping pairs for each island
for (i=0;i<dispatcher->getNumManifolds();i++)
{
btPersistentManifold* manifold = dispatcher->getManifoldByIndexInternal(i);
//filtering for response
btCollisionObject* colObj0 = static_cast<btCollisionObject*>(manifold->getBody0());
btCollisionObject* colObj1 = static_cast<btCollisionObject*>(manifold->getBody1());
{
int islandTag = colObj0->m_islandTag1;
if (colObj1->m_islandTag1 > islandTag)
islandTag = colObj1->m_islandTag1;
if (dispatcher->needsResponse(*colObj0,*colObj1))
simulationIslands[islandTag].m_manifolds.push_back(manifold);
}
}
#ifdef USE_QUICKPROF
btProfiler::endBlock("BuildIslands");
#endif //USE_QUICKPROF
#ifdef USE_QUICKPROF
btProfiler::beginBlock("SimulateIsland");
#endif //USE_QUICKPROF
btTypedConstraint** constraintBase = 0;
if (m_constraints.size())
constraintBase = &m_constraints[0];
assert(0);
/*
//Each simulation island can be processed in parallel (will be put on a job queue)
for (k=0;k<simulationIslands.size();k++)
{
if (simulationIslands[k].m_controllers.size())
{
assert(0);//seems to be wrong, passing ALL overlapping pairs
simulationIslands[k].Simulate(m_debugDrawer,m_numIterations, constraintBase ,&scene->GetOverlappingPair(0),dispatcher,getBroadphase(),m_solver,timeStep);
}
}
*/
#ifdef USE_QUICKPROF
btProfiler::endBlock("SimulateIsland");
#endif //USE_QUICKPROF
return true;
}

View File

@@ -1,44 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef PARALLELPHYSICSENVIRONMENT
#define PARALLELPHYSICSENVIRONMENT
#include "CcdPhysicsEnvironment.h"
class ParallelIslandDispatcher;
/// ParallelPhysicsEnvironment is experimental parallel mainloop for physics simulation
/// 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 ParallelPhysicsEnvironment : public CcdPhysicsEnvironment
{
public:
ParallelPhysicsEnvironment(ParallelIslandDispatcher* dispatcher=0, btOverlappingPairCache* pairCache=0);
virtual ~ParallelPhysicsEnvironment();
/// Perform an integration step of duration 'timeStep'.
virtual bool proceedDeltaTimeOneStep(float timeStep);
//void BuildSimulationIslands();
};
#endif //PARALLELPHYSICSENVIRONMENT

View File

@@ -1,465 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "SimulationIsland.h"
#include "LinearMath/btTransform.h"
#include "CcdPhysicsController.h"
#include "BulletCollision/BroadphaseCollision/btOverlappingPairCache.h"
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
#include "BulletDynamics/ConstraintSolver/btConstraintSolver.h"
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
#include "LinearMath/btIDebugDraw.h"
extern float gContactBreakingTreshold;
bool SimulationIsland::Simulate(btIDebugDraw* debugDrawer,int numSolverIterations,btTypedConstraint** constraintsBaseAddress,btBroadphasePair* overlappingPairBaseAddress, btDispatcher* dispatcher,btBroadphaseInterface* broadphase,class btConstraintSolver* solver,float timeStep)
{
#ifdef USE_QUICKPROF
btProfiler::beginBlock("predictIntegratedTransform");
#endif //USE_QUICKPROF
{
// std::vector<CcdPhysicsController*>::iterator i;
int k;
for (k=0;k<GetNumControllers();k++)
{
CcdPhysicsController* ctrl = m_controllers[k];
// 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();
if (body->IsActive())
{
if (!body->IsStatic())
{
body->applyForces( timeStep);
body->integrateVelocities( timeStep);
body->predictIntegratedTransform(timeStep,body->m_interpolationWorldTransform);
}
}
}
}
#ifdef USE_QUICKPROF
btProfiler::endBlock("predictIntegratedTransform");
#endif //USE_QUICKPROF
//BroadphaseInterface* scene = getBroadphase();
//
// collision detection (?)
//
#ifdef USE_QUICKPROF
btProfiler::beginBlock("dispatchAllCollisionPairs");
#endif //USE_QUICKPROF
// int numsubstep = m_numIterations;
btDispatcherInfo dispatchInfo;
dispatchInfo.m_timeStep = timeStep;
dispatchInfo.m_stepCount = 0;
dispatchInfo.m_enableSatConvex = false;//m_enableSatCollisionDetection;
dispatchInfo.m_debugDraw = debugDrawer;
std::vector<btBroadphasePair> overlappingPairs;
overlappingPairs.resize(this->m_overlappingPairIndices.size());
//gather overlapping pair info
unsigned int i;
for (i=0;i<m_overlappingPairIndices.size();i++)
{
overlappingPairs[i] = overlappingPairBaseAddress[m_overlappingPairIndices[i]];
}
//pairCache->refreshOverlappingPairs();
if (overlappingPairs.size())
{
assert(0);
//dispatcher->dispatchAllCollisionPairs(&overlappingPairs[0],overlappingPairs.size(),dispatchInfo);///numsubstep,g);
}
//scatter overlapping pair info, mainly the created algorithms/contact caches
for (i=0;i<m_overlappingPairIndices.size();i++)
{
overlappingPairBaseAddress[m_overlappingPairIndices[i]] = overlappingPairs[i];
}
#ifdef USE_QUICKPROF
btProfiler::endBlock("dispatchAllCollisionPairs");
#endif //USE_QUICKPROF
//contacts
#ifdef USE_QUICKPROF
btProfiler::beginBlock("solveConstraint");
#endif //USE_QUICKPROF
//solve the regular constraints (point 2 point, hinge, etc)
for (int g=0;g<numSolverIterations;g++)
{
//
// constraint solving
//
int i;
int numConstraints = m_constraintIndices.size();
//point to point constraints
for (i=0;i< numConstraints ; i++ )
{
btTypedConstraint* constraint = constraintsBaseAddress[m_constraintIndices[i]];
constraint->buildJacobian();
constraint->solveConstraint( timeStep );
}
}
#ifdef USE_QUICKPROF
btProfiler::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];
btRaycastVehicle* vehicle = wrapperVehicle->GetVehicle();
vehicle->updateVehicle( timeStep);
}
#endif //NEW_BULLET_VEHICLE_SUPPORT
*/
/*
btProfiler::beginBlock("CallbackTriggers");
#endif //USE_QUICKPROF
CallbackTriggers();
#ifdef USE_QUICKPROF
btProfiler::endBlock("CallbackTriggers");
}
*/
//btOverlappingPairCache* scene = getCollisionWorld()->getPairCache();
btContactSolverInfo solverInfo;
solverInfo.m_friction = 0.9f;
solverInfo.m_numIterations = numSolverIterations;
solverInfo.m_timeStep = timeStep;
solverInfo.m_restitution = 0.f;//m_restitution;
if (m_manifolds.size())
{
solver->solveGroup( &m_manifolds[0],m_manifolds.size(),solverInfo,0);
}
#ifdef USE_QUICKPROF
btProfiler::beginBlock("proceedToTransform");
#endif //USE_QUICKPROF
{
{
UpdateAabbs(debugDrawer,broadphase,timeStep);
float toi = 1.f;
//experimental continuous collision detection
/* if (m_ccdMode == 3)
{
btDispatcherInfo dispatchInfo;
dispatchInfo.m_timeStep = timeStep;
dispatchInfo.m_stepCount = 0;
dispatchInfo.m_dispatchFunc = btDispatcherInfo::DISPATCH_CONTINUOUS;
// getCollisionWorld()->getDispatcher()->dispatchAllCollisionPairs(scene,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;
btTransform predictedTrans;
btRigidBody* body = ctrl->getRigidBody();
if (body->IsActive())
{
if (!body->IsStatic())
{
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);
btRigidBody* 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 (true)
{
if (body->GetActivationState() == ISLAND_SLEEPING)
{
m_sleepingControllers.push_back(ctrl);
}
} else
{
if (ctrl->wantsSleeping())
{
m_sleepingControllers.push_back(ctrl);
}
}
}
}
#ifdef USE_QUICKPROF
btProfiler::endBlock("proceedToTransform");
btProfiler::beginBlock("SyncMotionStates");
#endif //USE_QUICKPROF
SyncMotionStates(timeStep);
#ifdef USE_QUICKPROF
btProfiler::endBlock("SyncMotionStates");
#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 SimulationIsland::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 SimulationIsland::UpdateAabbs(btIDebugDraw* debugDrawer,btBroadphaseInterface* scene,float timeStep)
{
std::vector<CcdPhysicsController*>::iterator i;
//
// update aabbs, only for moving objects (!)
//
for (i=m_controllers.begin();
!(i==m_controllers.end()); i++)
{
CcdPhysicsController* ctrl = (*i);
btRigidBody* body = ctrl->getRigidBody();
btPoint3 minAabb,maxAabb;
btCollisionShape* shapeinterface = ctrl->getCollisionShape();
shapeinterface->calculateTemporalAabb(body->getCenterOfMassTransform(),
body->getLinearVelocity(),
//body->getAngularVelocity(),
btVector3(0.f,0.f,0.f),//no angular effect for now //body->getAngularVelocity(),
timeStep,minAabb,maxAabb);
btVector3 manifoldExtraExtents(gContactBreakingTreshold,gContactBreakingTreshold,gContactBreakingTreshold);
minAabb -= manifoldExtraExtents;
maxAabb += manifoldExtraExtents;
btBroadphaseProxy* bp = body->m_broadphaseHandle;
if (bp)
{
btVector3 color (1,1,0);
/*
class btIDebugDraw* m_debugDrawer = 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() & btIDebugDraw::DBG_DrawAabb)
{
DrawAabb(m_debugDrawer,minAabb,maxAabb,color);
}
}
*/
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;
assert(0);
/*
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");
*/
}
}
}
}
}

View File

@@ -1,55 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef SIMULATION_ISLAND_H
#define SIMULATION_ISLAND_H
#include <vector>
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
///At the start of the simulation timestep the simulation islands are re-calculated
///During one timestep there is no merging or splitting of Simulation Islands
class SimulationIsland
{
public:
std::vector<class CcdPhysicsController*> m_controllers;
std::vector<class btPersistentManifold*> m_manifolds;
std::vector<int> m_overlappingPairIndices;
std::vector<int> m_constraintIndices;
bool Simulate(btIDebugDraw* debugDrawer,int numSolverIterations,class btTypedConstraint** constraintsBaseAddress,struct btBroadphasePair* overlappingPairBaseAddress, btDispatcher* dispatcher,btBroadphaseInterface* broadphase, class btConstraintSolver* solver, float timeStep);
int GetNumControllers()
{
return m_controllers.size();
}
void SyncMotionStates(float timeStep);
void UpdateAabbs(btIDebugDraw* debugDrawer,btBroadphaseInterface* broadphase,float timeStep);
};
#endif //SIMULATION_ISLAND_H

View File

@@ -1,10 +0,0 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}src ${BULLET_PHYSICS_SOURCE_DIR}/Extras/PhysicsInterface/Common }
)
ADD_LIBRARY(LibPhysicsCommonInterface
PHY_IMotionState.cpp
PHY_IPhysicsController.cpp
PHY_IPhysicsEnvironment.cpp
PHY_IVehicle.cpp
)

View File

@@ -1,5 +0,0 @@
SubDir TOP Extras PhysicsInterface Common ;
Library bulletphysicsinterfacecommon : [ Wildcard *.h *.cpp ] ;
InstallHeader [ Wildcard *.h ] ;

View File

@@ -1,92 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef __PHY_DYNAMIC_TYPES
#define __PHY_DYNAMIC_TYPES
class PHY_ResponseTable;
class PHY_Shape;
struct PHY__Vector3
{
float m_vec[4];
operator const float* () const
{
return &m_vec[0];
}
operator float* ()
{
return &m_vec[0];
}
};
//typedef float PHY__Vector3[4];
typedef enum
{
PHY_FH_RESPONSE,
PHY_SENSOR_RESPONSE, /* Touch Sensors */
PHY_CAMERA_RESPONSE, /* Visibility Culling */
PHY_OBJECT_RESPONSE, /* Object Dynamic Geometry Response */
PHY_STATIC_RESPONSE, /* Static Geometry Response */
PHY_NUM_RESPONSE
};
typedef struct PHY_CollData {
PHY__Vector3 m_point1; /* Point in object1 in world coordinates */
PHY__Vector3 m_point2; /* Point in object2 in world coordinates */
PHY__Vector3 m_normal; /* point2 - point1 */
} PHY_CollData;
typedef bool (*PHY_ResponseCallback)(void *client_data,
void *client_object1,
void *client_object2,
const PHY_CollData *coll_data);
/// PHY_PhysicsType enumerates all possible Physics Entities.
/// It is mainly used to create/add Physics Objects
typedef enum PHY_PhysicsType {
PHY_CONVEX_RIGIDBODY=16386,
PHY_CONCAVE_RIGIDBODY=16399,
PHY_CONVEX_FIXEDBODY=16388,//'collision object'
PHY_CONCAVE_FIXEDBODY=16401,
PHY_CONVEX_KINEMATICBODY=16387,//
PHY_CONCAVE_KINEMATICBODY=16400,
PHY_CONVEX_PHANTOMBODY=16398,
PHY_CONCAVE_PHANTOMBODY=16402
} PHY_PhysicsType;
/// PHY_ConstraintType enumerates all supported Constraint Types
typedef enum PHY_ConstraintType {
PHY_POINT2POINT_CONSTRAINT=1,
PHY_LINEHINGE_CONSTRAINT=2,
PHY_ANGULAR_CONSTRAINT = 3,//hinge without ball socket
PHY_VEHICLE_CONSTRAINT=11,//complex 'constraint' that turns a rigidbody into a vehicle
PHY_GENERIC_6DOF_CONSTRAINT=12,//can leave any of the 6 degree of freedom 'free' or 'locked'
} PHY_ConstraintType;
typedef float PHY_Vector3[3];
#endif //__PHY_DYNAMIC_TYPES

View File

@@ -1,22 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "PHY_IMotionState.h"
PHY_IMotionState::~PHY_IMotionState()
{
}

View File

@@ -1,42 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef PHY__MOTIONSTATE_H
#define PHY__MOTIONSTATE_H
/**
PHY_IMotionState is the Interface to explicitly synchronize the world transformation.
Default implementations for mayor graphics libraries like OpenGL and DirectX can be provided.
*/
class PHY_IMotionState
{
public:
virtual ~PHY_IMotionState();
virtual void getWorldPosition(float& posX,float& posY,float& posZ)=0;
virtual void getWorldScaling(float& scaleX,float& scaleY,float& scaleZ)=0;
virtual void getWorldOrientation(float& quatIma0,float& quatIma1,float& quatIma2,float& quatReal)=0;
virtual void setWorldPosition(float posX,float posY,float posZ)=0;
virtual void setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal)=0;
virtual void calculateWorldTransformations()=0;
};
#endif //PHY__MOTIONSTATE_H

View File

@@ -1,23 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "PHY_IPhysicsController.h"
PHY_IPhysicsController::~PHY_IPhysicsController()
{
}

View File

@@ -1,88 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef PHY_IPHYSICSCONTROLLER_H
#define PHY_IPHYSICSCONTROLLER_H
#include "PHY_DynamicTypes.h"
/**
PHY_IPhysicsController is the abstract simplified Interface to a physical object.
It contains the IMotionState and IDeformableMesh Interfaces.
*/
class PHY_IPhysicsController
{
public:
virtual ~PHY_IPhysicsController();
/**
SynchronizeMotionStates ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
*/
virtual bool SynchronizeMotionStates(float time)=0;
/**
WriteMotionStateToDynamics ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
*/
virtual void WriteMotionStateToDynamics(bool nondynaonly)=0;
virtual void WriteDynamicsToMotionState()=0;
// controller replication
virtual void PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl)=0;
// kinematic methods
virtual void RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local)=0;
virtual void RelativeRotate(const float drot[12],bool local)=0;
virtual void getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal)=0;
virtual void setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal)=0;
virtual void setPosition(float posX,float posY,float posZ)=0;
virtual void getPosition(PHY__Vector3& pos) const=0;
virtual void setScaling(float scaleX,float scaleY,float scaleZ)=0;
// physics methods
virtual void ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local)=0;
virtual void ApplyForce(float forceX,float forceY,float forceZ,bool local)=0;
virtual void SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local)=0;
virtual void SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local)=0;
virtual void applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ)=0;
virtual void SetActive(bool active)=0;
// reading out information from physics
virtual void GetLinearVelocity(float& linvX,float& linvY,float& linvZ)=0;
virtual void GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ)=0;
virtual void getReactionForce(float& forceX,float& forceY,float& forceZ)=0;
// dyna's that are rigidbody are free in orientation, dyna's with non-rigidbody are restricted
virtual void setRigidBody(bool rigid)=0;
// clientinfo for raycasts for example
virtual void* getNewClientInfo()=0;
virtual void setNewClientInfo(void* clientinfo)=0;
virtual PHY_IPhysicsController* GetReplica() {return 0;}
virtual void calcXform() =0;
virtual void setMargin(float margin) =0;
virtual float getMargin() const=0;
virtual float getRadius() const { return 0.f;}
PHY__Vector3 GetWorldPosition(PHY__Vector3& localpos);
};
#endif //PHY_IPHYSICSCONTROLLER_H

View File

@@ -1,26 +0,0 @@
/*
* Copyright (c) 2001-2005 Erwin Coumans <phy@erwincoumans.com>
*
* Permission to use, copy, modify, distribute and sell this software
* and its documentation for any purpose is hereby granted without fee,
* provided that the above copyright notice appear in all copies and
* that both that copyright notice and this permission notice appear
* in supporting documentation. Erwin Coumans makes no
* representations about the suitability of this software for any
* purpose. It is provided "as is" without express or implied warranty.
*
*/
#include "PHY_IPhysicsEnvironment.h"
/**
* Physics Environment takes care of stepping the simulation and is a container for physics entities (rigidbodies,constraints, materials etc.)
* A derived class may be able to 'construct' entities by loading and/or converting
*/
PHY_IPhysicsEnvironment::~PHY_IPhysicsEnvironment()
{
}

View File

@@ -1,60 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef _IPHYSICSENVIRONMENT
#define _IPHYSICSENVIRONMENT
#include <vector>
#include "PHY_DynamicTypes.h"
/**
* Physics Environment takes care of stepping the simulation and is a container for physics entities (rigidbodies,constraints, materials etc.)
* A derived class may be able to 'construct' entities by loading and/or converting
*/
class PHY_IPhysicsEnvironment
{
public:
virtual ~PHY_IPhysicsEnvironment();
/// Perform an integration step of duration 'timeStep'.
virtual bool proceedDeltaTime(double curTime,float timeStep)=0;
virtual void setGravity(float x,float y,float z)=0;
virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type,
float pivotX,float pivotY,float pivotZ,
float axisX,float axisY,float axisZ)=0;
virtual void removeConstraint(int constraintid)=0;
virtual float getAppliedImpulse(int constraintid){ return 0.f;}
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)=0;
//Methods for gamelogic collision/physics callbacks
//todo:
virtual void addSensor(PHY_IPhysicsController* ctrl)=0;
virtual void removeSensor(PHY_IPhysicsController* ctrl)=0;
virtual void addTouchCallback(int response_class, PHY_ResponseCallback callback, void *user)=0;
virtual void requestCollisionCallback(PHY_IPhysicsController* ctrl)=0;
virtual PHY_IPhysicsController* CreateSphereController(float radius,const PHY__Vector3& position) =0;
virtual PHY_IPhysicsController* CreateConeController(float coneradius,float coneheight)=0;
};
#endif //_IPHYSICSENVIRONMENT

View File

@@ -1,23 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "PHY_IVehicle.h"
PHY_IVehicle::~PHY_IVehicle()
{
}

View File

@@ -1,72 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef PHY_IVEHICLE_H
#define PHY_IVEHICLE_H
//PHY_IVehicle provides a generic interface for (raycast based) vehicles. Mostly targetting 4 wheel cars and 2 wheel motorbikes.
class PHY_IMotionState;
#include "PHY_DynamicTypes.h"
class PHY_IVehicle
{
public:
virtual ~PHY_IVehicle();
virtual void addWheel(
PHY_IMotionState* motionState,
PHY__Vector3 connectionPoint,
PHY__Vector3 downDirection,
PHY__Vector3 axleDirection,
float suspensionRestLength,
float wheelRadius,
bool hasSteering
) = 0;
virtual int getNumWheels() const = 0;
virtual void GetWheelPosition(int wheelIndex,float& posX,float& posY,float& posZ) const = 0;
virtual void GetWheelOrientationQuaternion(int wheelIndex,float& quatX,float& quatY,float& quatZ,float& quatW) const = 0;
virtual float GetWheelRotation(int wheelIndex) const = 0;
virtual int getUserConstraintId() const =0;
virtual int getUserConstraintType() const =0;
//some basic steering/braking/tuning/balancing (bikes)
virtual void setSteeringValue(float steering,int wheelIndex) = 0;
virtual void applyEngineForce(float force,int wheelIndex) = 0;
virtual void ApplyBraking(float braking,int wheelIndex) = 0;
virtual void SetWheelFriction(float friction,int wheelIndex) = 0;
virtual void SetSuspensionStiffness(float suspensionStiffness,int wheelIndex) = 0;
virtual void SetSuspensionDamping(float suspensionStiffness,int wheelIndex) = 0;
virtual void SetSuspensionCompression(float suspensionStiffness,int wheelIndex) = 0;
virtual void SetRollInfluence(float rollInfluence,int wheelIndex) = 0;
virtual void setCoordinateSystem(int rightIndex,int upIndex,int forwardIndex) =0;
};
#endif //PHY_IVEHICLE_H

View File

@@ -1,47 +0,0 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef PHY_PROPSH
#define PHY_PROPSH
class btCollisionShape;
// Properties of dynamic objects
struct PHY_ShapeProps {
float m_mass; // Total mass
float m_inertia; // Inertia, should be a tensor some time
float m_lin_drag; // Linear drag (air, water) 0 = concrete, 1 = vacuum
float m_ang_drag; // Angular drag
float m_friction_scaling[3]; // Scaling for anisotropic friction. Component in range [0, 1]
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?
btCollisionShape* m_shape;
};
// Properties of collidable objects (non-ghost objects)
struct PHY_MaterialProps {
float m_restitution; // restitution of energie after a collision 0 = inelastic, 1 = elastic
float m_friction; // Coulomb friction (= ratio between the normal en maximum friction force)
float m_fh_spring; // Spring constant (both linear and angular)
float m_fh_damping; // Damping factor (linear and angular) in range [0, 1]
float m_fh_distance; // The range above the surface where Fh is active.
bool m_fh_normal; // Should the object slide off slopes?
};
#endif //PHY_PROPSH

View File

@@ -1,128 +0,0 @@
# Microsoft Developer Studio Project File - Name="PhysicsInterface" - Package Owner=<4>
# Microsoft Developer Studio Generated Build File, Format Version 6.00
# ** DO NOT EDIT **
# TARGTYPE "Win32 (x86) Static Library" 0x0104
CFG=PhysicsInterface - Win32 Debug
!MESSAGE This is not a valid makefile. To build this project using NMAKE,
!MESSAGE use the Export Makefile command and run
!MESSAGE
!MESSAGE NMAKE /f "PhysicsInterface.mak".
!MESSAGE
!MESSAGE You can specify a configuration when running NMAKE
!MESSAGE by defining the macro CFG on the command line. For example:
!MESSAGE
!MESSAGE NMAKE /f "PhysicsInterface.mak" CFG="PhysicsInterface - Win32 Debug"
!MESSAGE
!MESSAGE Possible choices for configuration are:
!MESSAGE
!MESSAGE "PhysicsInterface - Win32 Release" (based on "Win32 (x86) Static Library")
!MESSAGE "PhysicsInterface - Win32 Debug" (based on "Win32 (x86) Static Library")
!MESSAGE
# Begin Project
# PROP AllowPerConfigDependencies 0
# PROP Scc_ProjName ""
# PROP Scc_LocalPath ""
CPP=cl.exe
RSC=rc.exe
!IF "$(CFG)" == "PhysicsInterface - Win32 Release"
# PROP BASE Use_MFC 0
# PROP BASE Use_Debug_Libraries 0
# PROP BASE Output_Dir "Release"
# PROP BASE Intermediate_Dir "Release"
# PROP BASE Target_Dir ""
# PROP Use_MFC 0
# PROP Use_Debug_Libraries 0
# PROP Output_Dir "Release"
# PROP Intermediate_Dir "Release"
# PROP Target_Dir ""
LINK32=link.exe -lib
MTL=midl.exe
# ADD BASE CPP /nologo /W3 /GX /O2 /D "WIN32" /D "NDEBUG" /D "_MBCS" /D "_LIB" /YX /FD /c
# ADD CPP /nologo /W3 /GX /O2 /I "..\..\..\LinearMath" /I "..\..\..\Extras\PhysicsInterface\Common" /D "WIN32" /D "NDEBUG" /D "_MBCS" /D "_LIB" /YX /FD /c
# ADD BASE RSC /l 0x809 /d "NDEBUG"
# ADD RSC /l 0x809 /d "NDEBUG"
BSC32=bscmake.exe
# ADD BASE BSC32 /nologo
# ADD BSC32 /nologo
LIB32=link.exe -lib
# ADD BASE LIB32 /nologo
# ADD LIB32 /nologo
!ELSEIF "$(CFG)" == "PhysicsInterface - Win32 Debug"
# PROP BASE Use_MFC 0
# PROP BASE Use_Debug_Libraries 1
# PROP BASE Output_Dir "Debug"
# PROP BASE Intermediate_Dir "Debug"
# PROP BASE Target_Dir ""
# PROP Use_MFC 0
# PROP Use_Debug_Libraries 1
# PROP Output_Dir "Debug"
# PROP Intermediate_Dir "Debug"
# PROP Target_Dir ""
LINK32=link.exe -lib
MTL=midl.exe
# ADD BASE CPP /nologo /W3 /Gm /GX /ZI /Od /D "WIN32" /D "_DEBUG" /D "_MBCS" /D "_LIB" /YX /FD /GZ /c
# ADD CPP /nologo /W3 /Gm /GX /ZI /Od /I "..\..\..\LinearMath" /I "..\..\..\Extras\PhysicsInterface\Common" /D "WIN32" /D "_DEBUG" /D "_MBCS" /D "_LIB" /YX /FD /GZ /c
# ADD BASE RSC /l 0x809 /d "_DEBUG"
# ADD RSC /l 0x809 /d "_DEBUG"
BSC32=bscmake.exe
# ADD BASE BSC32 /nologo
# ADD BSC32 /nologo
LIB32=link.exe -lib
# ADD BASE LIB32 /nologo
# ADD LIB32 /nologo
!ENDIF
# Begin Target
# Name "PhysicsInterface - Win32 Release"
# Name "PhysicsInterface - Win32 Debug"
# Begin Group "Source Files"
# PROP Default_Filter "cpp;c;cxx;rc;def;r;odl;idl;hpj;bat"
# Begin Source File
SOURCE=.\PHY_IMotionState.cpp
# End Source File
# Begin Source File
SOURCE=.\PHY_IPhysicsController.cpp
# End Source File
# Begin Source File
SOURCE=.\PHY_IPhysicsEnvironment.cpp
# End Source File
# End Group
# Begin Group "Header Files"
# PROP Default_Filter "h;hpp;hxx;hm;inl"
# Begin Source File
SOURCE=.\PHY_DynamicTypes.h
# End Source File
# Begin Source File
SOURCE=.\PHY_IMotionState.h
# End Source File
# Begin Source File
SOURCE=.\PHY_IPhysicsController.h
# End Source File
# Begin Source File
SOURCE=.\PHY_IPhysicsEnvironment.h
# End Source File
# Begin Source File
SOURCE=.\PHY_Pro.h
# End Source File
# End Group
# End Target
# End Project

View File

@@ -1,143 +0,0 @@
<?xml version="1.0" encoding="Windows-1252"?>
<VisualStudioProject
ProjectType="Visual C++"
Version="7.10"
Name="PhysicsInterfaceCommon"
ProjectGUID="{87D8C006-6DCC-4156-A03E-8CEA1B4C0580}"
Keyword="Win32Proj">
<Platforms>
<Platform
Name="Win32"/>
</Platforms>
<Configurations>
<Configuration
Name="Debug|Win32"
OutputDirectory="Debug"
IntermediateDirectory="Debug"
ConfigurationType="4"
CharacterSet="2">
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories="..\..\..\..\LinearMath"
PreprocessorDefinitions="WIN32;_DEBUG;_LIB"
MinimalRebuild="TRUE"
BasicRuntimeChecks="3"
RuntimeLibrary="3"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="TRUE"
DebugInformationFormat="4"/>
<Tool
Name="VCCustomBuildTool"/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/PhysicsInterfaceCommon.lib"/>
<Tool
Name="VCMIDLTool"/>
<Tool
Name="VCPostBuildEventTool"/>
<Tool
Name="VCPreBuildEventTool"/>
<Tool
Name="VCPreLinkEventTool"/>
<Tool
Name="VCResourceCompilerTool"/>
<Tool
Name="VCWebServiceProxyGeneratorTool"/>
<Tool
Name="VCXMLDataGeneratorTool"/>
<Tool
Name="VCManagedWrapperGeneratorTool"/>
<Tool
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
</Configuration>
<Configuration
Name="Release|Win32"
OutputDirectory="Release"
IntermediateDirectory="Release"
ConfigurationType="4"
CharacterSet="2">
<Tool
Name="VCCLCompilerTool"
AdditionalIncludeDirectories="..\..\..\..\LinearMath"
PreprocessorDefinitions="WIN32;NDEBUG;_LIB"
RuntimeLibrary="4"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="TRUE"
DebugInformationFormat="3"/>
<Tool
Name="VCCustomBuildTool"/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/PhysicsInterfaceCommon.lib"/>
<Tool
Name="VCMIDLTool"/>
<Tool
Name="VCPostBuildEventTool"/>
<Tool
Name="VCPreBuildEventTool"/>
<Tool
Name="VCPreLinkEventTool"/>
<Tool
Name="VCResourceCompilerTool"/>
<Tool
Name="VCWebServiceProxyGeneratorTool"/>
<Tool
Name="VCXMLDataGeneratorTool"/>
<Tool
Name="VCManagedWrapperGeneratorTool"/>
<Tool
Name="VCAuxiliaryManagedWrapperGeneratorTool"/>
</Configuration>
</Configurations>
<References>
</References>
<Files>
<Filter
Name="Source Files"
Filter="cpp;c;cxx;def;odl;idl;hpj;bat;asm;asmx"
UniqueIdentifier="{4FC737F1-C7A5-4376-A066-2A32D752A2FF}">
<File
RelativePath="..\PHY_IMotionState.cpp">
</File>
<File
RelativePath="..\PHY_IPhysicsController.cpp">
</File>
<File
RelativePath="..\PHY_IPhysicsEnvironment.cpp">
</File>
</Filter>
<Filter
Name="Header Files"
Filter="h;hpp;hxx;hm;inl;inc;xsd"
UniqueIdentifier="{93995380-89BD-4b04-88EB-625FBE52EBFB}">
<File
RelativePath="..\PHY_DynamicTypes.h">
</File>
<File
RelativePath="..\PHY_IMotionState.h">
</File>
<File
RelativePath="..\PHY_IPhysicsController.h">
</File>
<File
RelativePath="..\PHY_IPhysicsEnvironment.h">
</File>
<File
RelativePath="..\PHY_Pro.h">
</File>
</Filter>
<Filter
Name="Resource Files"
Filter="rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx"
UniqueIdentifier="{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}">
</Filter>
<File
RelativePath=".\ReadMe.txt">
</File>
</Files>
<Globals>
</Globals>
</VisualStudioProject>

View File

@@ -1,211 +0,0 @@
<?xml version="1.0" encoding="Windows-1252"?>
<VisualStudioProject
ProjectType="Visual C++"
Version="8.00"
Name="PhysicsInterfaceCommon"
ProjectGUID="{87D8C006-6DCC-4156-A03E-8CEA1B4C0580}"
Keyword="Win32Proj"
>
<Platforms>
<Platform
Name="Win32"
/>
</Platforms>
<ToolFiles>
</ToolFiles>
<Configurations>
<Configuration
Name="Debug|Win32"
OutputDirectory="Debug"
IntermediateDirectory="Debug"
ConfigurationType="4"
CharacterSet="2"
>
<Tool
Name="VCPreBuildEventTool"
/>
<Tool
Name="VCCustomBuildTool"
/>
<Tool
Name="VCXMLDataGeneratorTool"
/>
<Tool
Name="VCWebServiceProxyGeneratorTool"
/>
<Tool
Name="VCMIDLTool"
/>
<Tool
Name="VCCLCompilerTool"
Optimization="0"
AdditionalIncludeDirectories="..\..\..\..\LinearMath"
PreprocessorDefinitions="WIN32;_DEBUG;_LIB"
MinimalRebuild="true"
BasicRuntimeChecks="3"
RuntimeLibrary="1"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="true"
DebugInformationFormat="4"
/>
<Tool
Name="VCManagedResourceCompilerTool"
/>
<Tool
Name="VCResourceCompilerTool"
/>
<Tool
Name="VCPreLinkEventTool"
/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/PhysicsInterfaceCommon.lib"
/>
<Tool
Name="VCALinkTool"
/>
<Tool
Name="VCXDCMakeTool"
/>
<Tool
Name="VCBscMakeTool"
/>
<Tool
Name="VCFxCopTool"
/>
<Tool
Name="VCPostBuildEventTool"
/>
</Configuration>
<Configuration
Name="Release|Win32"
OutputDirectory="Release"
IntermediateDirectory="Release"
ConfigurationType="4"
CharacterSet="2"
>
<Tool
Name="VCPreBuildEventTool"
/>
<Tool
Name="VCCustomBuildTool"
/>
<Tool
Name="VCXMLDataGeneratorTool"
/>
<Tool
Name="VCWebServiceProxyGeneratorTool"
/>
<Tool
Name="VCMIDLTool"
/>
<Tool
Name="VCCLCompilerTool"
AdditionalIncludeDirectories="..\..\..\..\LinearMath"
PreprocessorDefinitions="WIN32;NDEBUG;_LIB"
RuntimeLibrary="0"
UsePrecompiledHeader="0"
WarningLevel="3"
Detect64BitPortabilityProblems="true"
DebugInformationFormat="3"
/>
<Tool
Name="VCManagedResourceCompilerTool"
/>
<Tool
Name="VCResourceCompilerTool"
/>
<Tool
Name="VCPreLinkEventTool"
/>
<Tool
Name="VCLibrarianTool"
OutputFile="$(OutDir)/PhysicsInterfaceCommon.lib"
/>
<Tool
Name="VCALinkTool"
/>
<Tool
Name="VCXDCMakeTool"
/>
<Tool
Name="VCBscMakeTool"
/>
<Tool
Name="VCFxCopTool"
/>
<Tool
Name="VCPostBuildEventTool"
/>
</Configuration>
</Configurations>
<References>
</References>
<Files>
<Filter
Name="Source Files"
Filter="cpp;c;cxx;def;odl;idl;hpj;bat;asm;asmx"
UniqueIdentifier="{4FC737F1-C7A5-4376-A066-2A32D752A2FF}"
>
<File
RelativePath="..\PHY_IMotionState.cpp"
>
</File>
<File
RelativePath="..\PHY_IPhysicsController.cpp"
>
</File>
<File
RelativePath="..\PHY_IPhysicsEnvironment.cpp"
>
</File>
<File
RelativePath="..\PHY_IVehicle.cpp"
>
</File>
</Filter>
<Filter
Name="Header Files"
Filter="h;hpp;hxx;hm;inl;inc;xsd"
UniqueIdentifier="{93995380-89BD-4b04-88EB-625FBE52EBFB}"
>
<File
RelativePath="..\PHY_DynamicTypes.h"
>
</File>
<File
RelativePath="..\PHY_IMotionState.h"
>
</File>
<File
RelativePath="..\PHY_IPhysicsController.h"
>
</File>
<File
RelativePath="..\PHY_IPhysicsEnvironment.h"
>
</File>
<File
RelativePath="..\PHY_IVehicle.h"
>
</File>
<File
RelativePath="..\PHY_Pro.h"
>
</File>
</Filter>
<Filter
Name="Resource Files"
Filter="rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx"
UniqueIdentifier="{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}"
>
</Filter>
<File
RelativePath=".\ReadMe.txt"
>
</File>
</Files>
<Globals>
</Globals>
</VisualStudioProject>

View File

@@ -1,4 +0,0 @@
SubDir TOP Extras PhysicsInterface ;
SubInclude TOP Extras PhysicsInterface Common ;
SubInclude TOP Extras PhysicsInterface CcdPhysics ;

View File

@@ -21,13 +21,33 @@ subject to the following restrictions:
#include "BulletCollision/CollisionShapes/btTriangleMeshShape.h" //for raycasting #include "BulletCollision/CollisionShapes/btTriangleMeshShape.h" //for raycasting
#include "BulletCollision/NarrowPhaseCollision/btRaycastCallback.h" #include "BulletCollision/NarrowPhaseCollision/btRaycastCallback.h"
#include "BulletCollision/CollisionShapes/btCompoundShape.h" #include "BulletCollision/CollisionShapes/btCompoundShape.h"
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h" #include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h" #include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "LinearMath/btAabbUtil2.h" #include "LinearMath/btAabbUtil2.h"
//When the user doesn't provide dispatcher or broadphase, create basic versions (and delete them in destructor)
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/BroadphaseCollision/btSimpleBroadphase.h"
#include <algorithm> #include <algorithm>
btCollisionWorld::btCollisionWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache)
:m_dispatcher1(dispatcher),
m_broadphasePairCache(pairCache),
m_ownsDispatcher(false),
m_ownsBroadphasePairCache(false)
{
}
btCollisionWorld::btCollisionWorld()
: m_dispatcher1(new btCollisionDispatcher()),
m_broadphasePairCache(new btSimpleBroadphase()),
m_ownsDispatcher(true),
m_ownsBroadphasePairCache(true)
{
}
btCollisionWorld::~btCollisionWorld() btCollisionWorld::~btCollisionWorld()
{ {
//clean up remaining objects //clean up remaining objects
@@ -50,6 +70,11 @@ btCollisionWorld::~btCollisionWorld()
} }
} }
if (m_ownsDispatcher)
delete m_dispatcher1;
if (m_ownsBroadphasePairCache)
delete m_broadphasePairCache;
} }
@@ -100,14 +125,14 @@ void btCollisionWorld::performDiscreteCollisionDetection()
{ {
m_collisionObjects[i]->m_cachedInvertedWorldTransform = m_collisionObjects[i]->m_worldTransform.inverse(); m_collisionObjects[i]->m_cachedInvertedWorldTransform = m_collisionObjects[i]->m_worldTransform.inverse();
m_collisionObjects[i]->m_collisionShape->getAabb(m_collisionObjects[i]->m_worldTransform,aabbMin,aabbMax); m_collisionObjects[i]->m_collisionShape->getAabb(m_collisionObjects[i]->m_worldTransform,aabbMin,aabbMax);
m_pairCache->setAabb(m_collisionObjects[i]->m_broadphaseHandle,aabbMin,aabbMax); m_broadphasePairCache->setAabb(m_collisionObjects[i]->m_broadphaseHandle,aabbMin,aabbMax);
} }
m_pairCache->refreshOverlappingPairs(); m_broadphasePairCache->refreshOverlappingPairs();
btDispatcher* dispatcher = getDispatcher(); btDispatcher* dispatcher = getDispatcher();
if (dispatcher) if (dispatcher)
dispatcher->dispatchAllCollisionPairs(m_pairCache,dispatchInfo); dispatcher->dispatchAllCollisionPairs(m_broadphasePairCache,dispatchInfo);
} }

View File

@@ -88,28 +88,30 @@ protected:
btDispatcher* m_dispatcher1; btDispatcher* m_dispatcher1;
btOverlappingPairCache* m_pairCache; btOverlappingPairCache* m_broadphasePairCache;
bool m_ownsDispatcher;
bool m_ownsBroadphasePairCache;
public: public:
btCollisionWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache) //this constructor will create and own a dispatcher and paircache and delete it at destruction
:m_dispatcher1(dispatcher), btCollisionWorld();
m_pairCache(pairCache)
{ //this constructor doesn't own the dispatcher and paircache/broadphase
btCollisionWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache);
}
virtual ~btCollisionWorld(); virtual ~btCollisionWorld();
btBroadphaseInterface* getBroadphase() btBroadphaseInterface* getBroadphase()
{ {
return m_pairCache; return m_broadphasePairCache;
} }
btOverlappingPairCache* getPairCache() btOverlappingPairCache* getPairCache()
{ {
return m_pairCache; return m_broadphasePairCache;
} }

View File

@@ -36,10 +36,13 @@ subject to the following restrictions:
#include <algorithm> #include <algorithm>
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld() btDiscreteDynamicsWorld::btDiscreteDynamicsWorld()
:btDynamicsWorld(new btCollisionDispatcher(),new btSimpleBroadphase()), :btDynamicsWorld(),
m_constraintSolver(new btSequentialImpulseConstraintSolver) m_constraintSolver(new btSequentialImpulseConstraintSolver)
{ {
m_islandManager = new btSimulationIslandManager(); m_islandManager = new btSimulationIslandManager();
m_ownsIslandManager = true;
m_ownsConstraintSolver = true;
} }
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver) btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
@@ -47,20 +50,18 @@ btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOver
m_constraintSolver(constraintSolver) m_constraintSolver(constraintSolver)
{ {
m_islandManager = new btSimulationIslandManager(); m_islandManager = new btSimulationIslandManager();
m_ownsIslandManager = true;
m_ownsConstraintSolver = false;
} }
btDiscreteDynamicsWorld::~btDiscreteDynamicsWorld() btDiscreteDynamicsWorld::~btDiscreteDynamicsWorld()
{ {
delete m_islandManager ; //only delete it when we created it
if (m_ownsIslandManager)
delete m_constraintSolver; delete m_islandManager;
if (m_ownsConstraintSolver)
//delete the dispatcher and paircache delete m_constraintSolver;
delete m_dispatcher1;
m_dispatcher1 = 0;
delete m_pairCache;
m_pairCache = 0;
} }
void btDiscreteDynamicsWorld::stepSimulation(float timeStep) void btDiscreteDynamicsWorld::stepSimulation(float timeStep)
@@ -291,7 +292,7 @@ void btDiscreteDynamicsWorld::updateAabbs()
{ {
btPoint3 minAabb,maxAabb; btPoint3 minAabb,maxAabb;
colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb); colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_pairCache; btSimpleBroadphase* bp = (btSimpleBroadphase*)m_broadphasePairCache;
bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb); bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
} }
} }

View File

@@ -40,6 +40,9 @@ protected:
std::vector<btTypedConstraint*> m_constraints; std::vector<btTypedConstraint*> m_constraints;
bool m_ownsIslandManager;
bool m_ownsConstraintSolver;
std::vector<btRaycastVehicle*> m_vehicles; std::vector<btRaycastVehicle*> m_vehicles;
void predictUnconstraintMotion(float timeStep); void predictUnconstraintMotion(float timeStep);
@@ -61,8 +64,10 @@ protected:
public: public:
///this btDiscreteDynamicsWorld constructor gets created objects from the user, and will not delete those
btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver); btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver);
///this btDiscreteDynamicsWorld will create and own dispatcher, pairCache and constraintSolver, and deletes it in the destructor.
btDiscreteDynamicsWorld(); btDiscreteDynamicsWorld();
virtual ~btDiscreteDynamicsWorld(); virtual ~btDiscreteDynamicsWorld();

View File

@@ -24,11 +24,15 @@ class btDynamicsWorld : public btCollisionWorld
{ {
public: public:
btDynamicsWorld()
{
}
btDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache) btDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache)
:btCollisionWorld(dispatcher,pairCache) :btCollisionWorld(dispatcher,pairCache)
{ {
} }
virtual ~btDynamicsWorld() virtual ~btDynamicsWorld()
{ {
} }

View File

@@ -23,15 +23,15 @@ subject to the following restrictions:
btSimpleDynamicsWorld::btSimpleDynamicsWorld() btSimpleDynamicsWorld::btSimpleDynamicsWorld()
:btDynamicsWorld(new btCollisionDispatcher(),new btSimpleBroadphase()), :m_constraintSolver(new btSequentialImpulseConstraintSolver),
m_constraintSolver(new btSequentialImpulseConstraintSolver) m_ownsConstraintSolver(true)
{ {
} }
btSimpleDynamicsWorld::btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver) btSimpleDynamicsWorld::btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
:btDynamicsWorld(dispatcher,pairCache), :btDynamicsWorld(dispatcher,pairCache),
m_constraintSolver(constraintSolver) m_constraintSolver(constraintSolver),
m_ownsConstraintSolver(false)
{ {
} }
@@ -39,13 +39,8 @@ m_constraintSolver(constraintSolver)
btSimpleDynamicsWorld::~btSimpleDynamicsWorld() btSimpleDynamicsWorld::~btSimpleDynamicsWorld()
{ {
delete m_constraintSolver; if (m_ownsConstraintSolver)
delete m_constraintSolver;
//delete the dispatcher and paircache
delete m_dispatcher1;
m_dispatcher1 = 0;
delete m_pairCache;
m_pairCache = 0;
} }
void btSimpleDynamicsWorld::stepSimulation(float timeStep) void btSimpleDynamicsWorld::stepSimulation(float timeStep)
@@ -86,7 +81,7 @@ void btSimpleDynamicsWorld::updateAabbs()
{ {
btPoint3 minAabb,maxAabb; btPoint3 minAabb,maxAabb;
colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb); colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_pairCache; btBroadphaseInterface* bp = getBroadphase();
bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb); bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
} }
} }

View File

@@ -33,6 +33,8 @@ protected:
btConstraintSolver* m_constraintSolver; btConstraintSolver* m_constraintSolver;
bool m_ownsConstraintSolver;
void predictUnconstraintMotion(float timeStep); void predictUnconstraintMotion(float timeStep);
void integrateTransforms(float timeStep); void integrateTransforms(float timeStep);
@@ -42,10 +44,12 @@ protected:
public: public:
btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver); ///this btSimpleDynamicsWorld constructor creates and owns dispatcher, broadphase pairCache and constraintSolver
btSimpleDynamicsWorld(); btSimpleDynamicsWorld();
///this btSimpleDynamicsWorld constructor creates dispatcher, broadphase pairCache and constraintSolver
btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver);
virtual ~btSimpleDynamicsWorld(); virtual ~btSimpleDynamicsWorld();
virtual void stepSimulation( float timeStep); virtual void stepSimulation( float timeStep);