moved files around

This commit is contained in:
ejcoumans
2006-05-25 19:18:29 +00:00
commit e061ec1ebf
1024 changed files with 349445 additions and 0 deletions

View File

@@ -0,0 +1,112 @@
# 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

@@ -0,0 +1,584 @@
/*
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 "Dynamics/RigidBody.h"
#include "PHY_IMotionState.h"
#include "BroadphaseCollision/BroadphaseProxy.h"
#include "BroadphaseCollision/BroadphaseInterface.h"
#include "CollisionShapes/ConvexShape.h"
#include "CcdPhysicsEnvironment.h"
#include "SimdTransformUtil.h"
#include "CollisionShapes/SphereShape.h"
#include "CollisionShapes/ConeShape.h"
class BP_Proxy;
///todo: fill all the empty CcdPhysicsController methods, hook them up to the RigidBody class
//'temporarily' global variables
float gDeactivationTime = 2.f;
bool gDisableDeactivation = false;
float gLinearSleepingTreshold = 0.8f;
float gAngularSleepingTreshold = 1.0f;
#include "Dynamics/MassProps.h"
SimdVector3 startVel(0,0,0);//-10000);
CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& 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
}
SimdTransform CcdPhysicsController::GetTransformFromMotionState(PHY_IMotionState* motionState)
{
SimdTransform trans;
float tmp[3];
motionState->getWorldPosition(tmp[0],tmp[1],tmp[2]);
trans.setOrigin(SimdVector3(tmp[0],tmp[1],tmp[2]));
SimdQuaternion orn;
motionState->getWorldOrientation(orn[0],orn[1],orn[2],orn[3]);
trans.setRotation(orn);
return trans;
}
void CcdPhysicsController::CreateRigidbody()
{
SimdTransform trans = GetTransformFromMotionState(m_cci.m_MotionState);
MassProps mp(m_cci.m_mass, m_cci.m_localInertiaTensor);
m_body = new RigidBody(mp,0,0,m_cci.m_friction,m_cci.m_restitution);
m_body->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
m_cci.m_physicsEnv->removeCcdPhysicsController(this);
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 SimdVector3& worldPos = m_body->getCenterOfMassPosition();
m_MotionState->setWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
const SimdQuaternion& worldquat = m_body->getOrientation();
m_MotionState->setWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
m_MotionState->calculateWorldTransformations();
float scale[3];
m_MotionState->getWorldScaling(scale[0],scale[1],scale[2]);
SimdVector3 scaling(scale[0],scale[1],scale[2]);
GetCollisionShape()->setLocalScaling(scaling);
} else
{
SimdVector3 worldPos;
SimdQuaternion worldquat;
m_MotionState->getWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
m_MotionState->getWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
SimdTransform oldTrans = m_body->getCenterOfMassTransform();
SimdTransform newTrans(worldquat,worldPos);
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]);
SimdVector3 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();
SimdVector3 dloc(dlocX,dlocY,dlocZ);
SimdTransform 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();
SimdMatrix3x3 drotmat( rotval[0],rotval[1],rotval[2],
rotval[4],rotval[5],rotval[6],
rotval[8],rotval[9],rotval[10]);
SimdMatrix3x3 currentOrn;
GetWorldOrientation(currentOrn);
SimdTransform xform = m_body->getCenterOfMassTransform();
xform.setBasis(xform.getBasis()*(local ?
drotmat : (currentOrn.inverse() * drotmat * currentOrn)));
m_body->setCenterOfMassTransform(xform);
}
}
void CcdPhysicsController::GetWorldOrientation(SimdMatrix3x3& mat)
{
float orn[4];
m_MotionState->getWorldOrientation(orn[0],orn[1],orn[2],orn[3]);
SimdQuaternion quat(orn[0],orn[1],orn[2],orn[3]);
mat.setRotation(quat);
}
void CcdPhysicsController::getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal)
{
SimdQuaternion 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();
SimdTransform xform = m_body->getCenterOfMassTransform();
xform.setRotation(SimdQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
m_body->setCenterOfMassTransform(xform);
}
void CcdPhysicsController::setPosition(float posX,float posY,float posZ)
{
m_body->activate();
SimdTransform xform = m_body->getCenterOfMassTransform();
xform.setOrigin(SimdVector3(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 SimdTransform& 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 (!SimdFuzzyZero(m_cci.m_scaling.x()-scaleX) ||
!SimdFuzzyZero(m_cci.m_scaling.y()-scaleY) ||
!SimdFuzzyZero(m_cci.m_scaling.z()-scaleZ))
{
m_cci.m_scaling = SimdVector3(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)
{
SimdVector3 torque(torqueX,torqueY,torqueZ);
SimdTransform 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)
{
SimdVector3 force(forceX,forceY,forceZ);
SimdTransform 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)
{
SimdVector3 angvel(ang_velX,ang_velY,ang_velZ);
if (angvel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
{
m_body->activate();
}
{
SimdTransform 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)
{
SimdVector3 linVel(lin_velX,lin_velY,lin_velZ);
if (linVel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
{
m_body->activate();
}
{
SimdTransform 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)
{
SimdVector3 impulse(impulseX,impulseY,impulseZ);
if (impulse.length2() > (SIMD_EPSILON*SIMD_EPSILON))
{
m_body->activate();
SimdVector3 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 SimdVector3& linvel = this->m_body->getLinearVelocity();
linvX = linvel.x();
linvY = linvel.y();
linvZ = linvel.z();
}
void CcdPhysicsController::GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ)
{
const SimdVector3& 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)
{
SimdVector3 pos(posX,posY,posZ);
SimdVector3 rel_pos = pos-m_body->getCenterOfMassPosition();
SimdVector3 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
SimdVector3 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 SphereShape/ConeShape for now
CcdConstructionInfo cinfo = m_cci;
if (cinfo.m_collisionShape)
{
switch (cinfo.m_collisionShape->GetShapeType())
{
case SPHERE_SHAPE_PROXYTYPE:
{
SphereShape* orgShape = (SphereShape*)cinfo.m_collisionShape;
cinfo.m_collisionShape = new SphereShape(*orgShape);
break;
}
case CONE_SHAPE_PROXYTYPE:
{
ConeShape* orgShape = (ConeShape*)cinfo.m_collisionShape;
cinfo.m_collisionShape = new ConeShape(*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();
}
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 = 1.;
scaleY = 1.;
scaleZ = 1.;
}
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)
{
SimdPoint3 pos(posX,posY,posZ);
m_worldTransform.setOrigin( pos );
}
void DefaultMotionState::setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal)
{
SimdQuaternion orn(quatIma0,quatIma1,quatIma2,quatReal);
m_worldTransform.setRotation( orn );
}
void DefaultMotionState::calculateWorldTransformations()
{
}

View File

@@ -0,0 +1,215 @@
/*
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 "SimdVector3.h"
#include "SimdScalar.h"
#include "SimdMatrix3x3.h"
#include "SimdTransform.h"
#include "Dynamics/RigidBody.h"
#include "PHY_IMotionState.h"
#include "BroadphaseCollision/BroadphaseProxy.h" //for CollisionShape access
class CollisionShape;
extern float gDeactivationTime;
extern float gLinearSleepingTreshold;
extern float gAngularSleepingTreshold;
extern bool gDisableDeactivation;
class CcdPhysicsEnvironment;
struct CcdConstructionInfo
{
CcdConstructionInfo()
: m_gravity(0,0,0),
m_mass(0.f),
m_restitution(0.1f),
m_friction(0.5f),
m_linearDamping(0.1f),
m_angularDamping(0.1f),
m_MotionState(0),
m_physicsEnv(0),
m_inertiaFactor(1.f),
m_scaling(1.f,1.f,1.f),
m_collisionFlags(0)
{
}
SimdVector3 m_localInertiaTensor;
SimdVector3 m_gravity;
SimdVector3 m_scaling;
SimdScalar m_mass;
SimdScalar m_restitution;
SimdScalar m_friction;
SimdScalar m_linearDamping;
SimdScalar m_angularDamping;
int m_collisionFlags;
CollisionShape* m_collisionShape;
class PHY_IMotionState* m_MotionState;
CcdPhysicsEnvironment* m_physicsEnv; //needed for self-replication
float m_inertiaFactor;//tweak the inertia (hooked up to Blender 'formfactor'
};
class RigidBody;
///CcdPhysicsController is a physics object that supports continuous collision detection and time of impact based physics resolution.
class CcdPhysicsController : public PHY_IPhysicsController
{
RigidBody* m_body;
class PHY_IMotionState* m_MotionState;
void* m_newClientInfo;
CcdConstructionInfo m_cci;//needed for replication
void GetWorldOrientation(SimdMatrix3x3& mat);
void CreateRigidbody();
public:
int m_collisionDelay;
CcdPhysicsController (const CcdConstructionInfo& ci);
virtual ~CcdPhysicsController();
RigidBody* GetRigidBody() { return m_body;}
CollisionShape* 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();
virtual void calcXform() {} ;
virtual void SetMargin(float margin) {};
virtual float GetMargin() const {return 0.f;};
bool wantsSleeping();
void UpdateDeactivation(float timeStep);
static SimdTransform GetTransformFromMotionState(PHY_IMotionState* motionState);
void SetAabb(const SimdVector3& aabbMin,const SimdVector3& aabbMax);
class PHY_IMotionState* GetMotionState()
{
return m_MotionState;
}
const class PHY_IMotionState* GetMotionState() const
{
return m_MotionState;
}
};
///DefaultMotionState implements standard motionstate, using SimdTransform
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();
SimdTransform m_worldTransform;
};
#endif //BULLET2_PHYSICSCONTROLLER_H

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,211 @@
/*
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 "SimdVector3.h"
class TypedConstraint;
class CollisionDispatcher;
class Dispatcher;
//#include "BroadphaseInterface.h"
//switch on/off new vehicle support
//#define NEW_BULLET_VEHICLE_SUPPORT 1
#include "ConstraintSolver/ContactSolverInfo.h"
class WrapperVehicle;
class PersistentManifold;
class BroadphaseInterface;
class IDebugDraw;
/// CcdPhysicsEnvironment is experimental mainloop for physics simulation using optional continuous collision detection.
/// Physics Environment takes care of stepping the simulation and is a container for physics entities.
/// It stores rigidbodies,constraints, materials etc.
/// A derived class may be able to 'construct' entities by loading and/or converting
class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
{
SimdVector3 m_gravity;
IDebugDraw* m_debugDrawer;
//solver iterations
int m_numIterations;
//timestep subdivisions
int m_numTimeSubSteps;
int m_ccdMode;
int m_solverType;
int m_profileTimings;
bool m_enableSatCollisionDetection;
ContactSolverInfo m_solverInfo;
public:
CcdPhysicsEnvironment(CollisionDispatcher* dispatcher=0, BroadphaseInterface* broadphase=0);
virtual ~CcdPhysicsEnvironment();
/////////////////////////////////////
//PHY_IPhysicsEnvironment interface
/////////////////////////////////////
/// Perform an integration step of duration 'timeStep'.
virtual void setDebugDrawer(IDebugDraw* 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);
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);
virtual void removeConstraint(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
TypedConstraint* 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);
BroadphaseInterface* GetBroadphase();
CollisionDispatcher* GetDispatcher();
const CollisionDispatcher* GetDispatcher() const;
bool IsSatCollisionDetectionEnabled() const
{
return m_enableSatCollisionDetection;
}
void EnableSatCollisionDetection(bool enableSat)
{
m_enableSatCollisionDetection = enableSat;
}
void UpdateAabbs(float timeStep);
int GetNumControllers();
CcdPhysicsController* GetPhysicsController( int index);
int GetNumManifolds() const;
const PersistentManifold* GetManifold(int index) const;
std::vector<TypedConstraint*> m_constraints;
private:
void SyncMotionStates(float timeStep);
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 CollisionWorld* m_collisionWorld;
class ConstraintSolver* m_solver;
bool m_scalingPropagated;
};
#endif //CCDPHYSICSENVIRONMENT

View File

@@ -0,0 +1,131 @@
<?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

@@ -0,0 +1,191 @@
<?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

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

View File

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

View File

@@ -0,0 +1,92 @@
/*
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_ConstraintType;
typedef float PHY_Vector3[3];
#endif //__PHY_DYNAMIC_TYPES

View File

@@ -0,0 +1,22 @@
/*
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

@@ -0,0 +1,42 @@
/*
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

@@ -0,0 +1,23 @@
/*
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

@@ -0,0 +1,88 @@
/*
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

@@ -0,0 +1,26 @@
/*
* 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

@@ -0,0 +1,58 @@
/*
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 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

@@ -0,0 +1,23 @@
/*
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

@@ -0,0 +1,61 @@
/*
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;
};
#endif //PHY_IVEHICLE_H

View File

@@ -0,0 +1,47 @@
/*
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 CollisionShape;
// 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?
CollisionShape* 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

@@ -0,0 +1,128 @@
# 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

@@ -0,0 +1,143 @@
<?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

@@ -0,0 +1,211 @@
<?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

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