merged most of the changes from the branch into trunk, except for COLLADA, libxml and glut glitches.
Still need to verify to make sure no unwanted renaming is introduced.
This commit is contained in:
@@ -321,4 +321,328 @@ void btDiscreteDynamicsWorld::predictUnconstraintMotion(float timeStep)
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}=======
|
||||
|
||||
#include "btDiscreteDynamicsWorld.h"
|
||||
|
||||
//collision detection
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btSimpleBroadphase.h"
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
|
||||
|
||||
//rigidbody & constraints
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
|
||||
//vehicle
|
||||
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
|
||||
#include "BulletDynamics/Vehicle/btVehicleRaycaster.h"
|
||||
#include "BulletDynamics/Vehicle/btWheelInfo.h"
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld()
|
||||
:btDynamicsWorld(new btCollisionDispatcher(),new btSimpleBroadphase()),
|
||||
m_constraintSolver(new btSequentialImpulseConstraintSolver)
|
||||
{
|
||||
m_islandManager = new btSimulationIslandManager();
|
||||
}
|
||||
|
||||
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
|
||||
:btDynamicsWorld(dispatcher,pairCache),
|
||||
m_constraintSolver(constraintSolver)
|
||||
{
|
||||
m_islandManager = new btSimulationIslandManager();
|
||||
}
|
||||
|
||||
|
||||
btDiscreteDynamicsWorld::~btDiscreteDynamicsWorld()
|
||||
{
|
||||
delete m_islandManager ;
|
||||
|
||||
delete m_constraintSolver;
|
||||
|
||||
//delete the dispatcher and paircache
|
||||
delete m_dispatcher1;
|
||||
m_dispatcher1 = 0;
|
||||
delete m_pairCache;
|
||||
m_pairCache = 0;
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::stepSimulation(float timeStep)
|
||||
{
|
||||
///update aabbs information
|
||||
updateAabbs();
|
||||
|
||||
///apply gravity, predict motion
|
||||
predictUnconstraintMotion(timeStep);
|
||||
|
||||
///perform collision detection
|
||||
PerformDiscreteCollisionDetection();
|
||||
|
||||
calculateSimulationIslands();
|
||||
|
||||
btContactSolverInfo infoGlobal;
|
||||
infoGlobal.m_timeStep = timeStep;
|
||||
|
||||
///solve non-contact constraints
|
||||
solveNoncontactConstraints(infoGlobal);
|
||||
|
||||
///solve contact constraints
|
||||
solveContactConstraints(infoGlobal);
|
||||
|
||||
///update vehicle simulation
|
||||
updateVehicles(timeStep);
|
||||
|
||||
///CallbackTriggers();
|
||||
|
||||
///integrate transforms
|
||||
integrateTransforms(timeStep);
|
||||
|
||||
updateActivationState( timeStep );
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::updateVehicles(float timeStep)
|
||||
{
|
||||
for (int i=0;i<m_vehicles.size();i++)
|
||||
{
|
||||
btRaycastVehicle* vehicle = m_vehicles[i];
|
||||
vehicle->UpdateVehicle( timeStep);
|
||||
}
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::updateActivationState(float timeStep)
|
||||
{
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
|
||||
body->updateDeactivation(timeStep);
|
||||
|
||||
if (body->wantsSleeping())
|
||||
{
|
||||
if (body->GetActivationState() == ACTIVE_TAG)
|
||||
body->SetActivationState( WANTS_DEACTIVATION );
|
||||
} else
|
||||
{
|
||||
if (body->GetActivationState() != DISABLE_DEACTIVATION)
|
||||
body->SetActivationState( ACTIVE_TAG );
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::addConstraint(btTypedConstraint* constraint)
|
||||
{
|
||||
m_constraints.push_back(constraint);
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::removeConstraint(btTypedConstraint* constraint)
|
||||
{
|
||||
std::vector<btTypedConstraint*>::iterator cit = std::find(m_constraints.begin(),m_constraints.end(),constraint);
|
||||
if (!(cit==m_constraints.end()))
|
||||
{
|
||||
m_constraints.erase(cit);
|
||||
}
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::addVehicle(btRaycastVehicle* vehicle)
|
||||
{
|
||||
m_vehicles.push_back(vehicle);
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::removeVehicle(btRaycastVehicle* vehicle)
|
||||
{
|
||||
std::vector<btRaycastVehicle*>::iterator vit = std::find(m_vehicles.begin(),m_vehicles.end(),vehicle);
|
||||
if (!(vit==m_vehicles.end()))
|
||||
{
|
||||
m_vehicles.erase(vit);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void btDiscreteDynamicsWorld::solveContactConstraints(btContactSolverInfo& solverInfo)
|
||||
{
|
||||
|
||||
struct InplaceSolverIslandCallback : public btSimulationIslandManager::IslandCallback
|
||||
{
|
||||
|
||||
btContactSolverInfo& m_solverInfo;
|
||||
btConstraintSolver* m_solver;
|
||||
btIDebugDraw* m_debugDrawer;
|
||||
|
||||
InplaceSolverIslandCallback(
|
||||
btContactSolverInfo& solverInfo,
|
||||
btConstraintSolver* solver,
|
||||
btIDebugDraw* debugDrawer)
|
||||
:m_solverInfo(solverInfo),
|
||||
m_solver(solver),
|
||||
m_debugDrawer(debugDrawer)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
virtual void ProcessIsland(btPersistentManifold** manifolds,int numManifolds)
|
||||
{
|
||||
m_solver->SolveGroup( manifolds, numManifolds,m_solverInfo,m_debugDrawer);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
btIDebugDraw* debugDraw = 0;
|
||||
InplaceSolverIslandCallback solverCallback( solverInfo, m_constraintSolver, debugDraw);
|
||||
|
||||
|
||||
/// solve all the contact points and contact friction
|
||||
m_islandManager->BuildAndProcessIslands(GetCollisionWorld()->GetDispatcher(),GetCollisionWorld()->GetCollisionObjectArray(),&solverCallback);
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
void btDiscreteDynamicsWorld::solveNoncontactConstraints(btContactSolverInfo& solverInfo)
|
||||
{
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("SolveConstraint");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
|
||||
int i;
|
||||
int numConstraints = m_constraints.size();
|
||||
|
||||
///constraint preparation: building jacobians
|
||||
for (i=0;i< numConstraints ; i++ )
|
||||
{
|
||||
btTypedConstraint* constraint = m_constraints[i];
|
||||
constraint->BuildJacobian();
|
||||
}
|
||||
|
||||
//solve the regular non-contact constraints (point 2 point, hinge, generic d6)
|
||||
for (int g=0;g<solverInfo.m_numIterations;g++)
|
||||
{
|
||||
//
|
||||
// constraint solving
|
||||
//
|
||||
for (i=0;i< numConstraints ; i++ )
|
||||
{
|
||||
btTypedConstraint* constraint = m_constraints[i];
|
||||
constraint->SolveConstraint( solverInfo.m_timeStep );
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("SolveConstraint");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::calculateSimulationIslands()
|
||||
{
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::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
|
||||
Profiler::endBlock("IslandUnionFind");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::updateAabbs()
|
||||
{
|
||||
btTransform predictedTrans;
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
btPoint3 minAabb,maxAabb;
|
||||
colObj->m_collisionShape->GetAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_pairCache;
|
||||
bp->SetAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::integrateTransforms(float timeStep)
|
||||
{
|
||||
btTransform predictedTrans;
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->predictIntegratedTransform(timeStep, predictedTrans);
|
||||
body->proceedToTransform( predictedTrans);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btDiscreteDynamicsWorld::predictUnconstraintMotion(float timeStep)
|
||||
{
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->applyForces( timeStep);
|
||||
body->integrateVelocities( timeStep);
|
||||
body->predictIntegratedTransform(timeStep,body->m_interpolationWorldTransform);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -94,4 +94,101 @@ public:
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DISCRETE_DYNAMICS_WORLD_H
|
||||
#endif //BT_DISCRETE_DYNAMICS_WORLD_H=======
|
||||
/*
|
||||
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 BT_DISCRETE_DYNAMICS_WORLD_H
|
||||
#define BT_DISCRETE_DYNAMICS_WORLD_H
|
||||
|
||||
#include "btDynamicsWorld.h"
|
||||
|
||||
class btDispatcher;
|
||||
class btOverlappingPairCache;
|
||||
class btConstraintSolver;
|
||||
class btSimulationIslandManager;
|
||||
class btTypedConstraint;
|
||||
struct btContactSolverInfo;
|
||||
class btRaycastVehicle;
|
||||
|
||||
#include <vector>
|
||||
|
||||
///btDiscreteDynamicsWorld provides discrete rigid body simulation
|
||||
///those classes replace the obsolete CcdPhysicsEnvironment/CcdPhysicsController
|
||||
class btDiscreteDynamicsWorld : public btDynamicsWorld
|
||||
{
|
||||
protected:
|
||||
|
||||
btConstraintSolver* m_constraintSolver;
|
||||
|
||||
btSimulationIslandManager* m_islandManager;
|
||||
|
||||
std::vector<btTypedConstraint*> m_constraints;
|
||||
|
||||
std::vector<btRaycastVehicle*> m_vehicles;
|
||||
|
||||
void predictUnconstraintMotion(float timeStep);
|
||||
|
||||
void integrateTransforms(float timeStep);
|
||||
|
||||
void updateAabbs();
|
||||
|
||||
void calculateSimulationIslands();
|
||||
|
||||
void solveNoncontactConstraints(btContactSolverInfo& solverInfo);
|
||||
|
||||
void solveContactConstraints(btContactSolverInfo& solverInfo);
|
||||
|
||||
void updateActivationState(float timeStep);
|
||||
|
||||
void updateVehicles(float timeStep);
|
||||
|
||||
public:
|
||||
|
||||
|
||||
btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver);
|
||||
|
||||
btDiscreteDynamicsWorld();
|
||||
|
||||
virtual ~btDiscreteDynamicsWorld();
|
||||
|
||||
virtual void stepSimulation( float timeStep);
|
||||
|
||||
void addConstraint(btTypedConstraint* constraint);
|
||||
|
||||
void removeConstraint(btTypedConstraint* constraint);
|
||||
|
||||
void addVehicle(btRaycastVehicle* vehicle);
|
||||
|
||||
void removeVehicle(btRaycastVehicle* vehicle);
|
||||
|
||||
btSimulationIslandManager* GetSimulationIslandManager()
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
const btSimulationIslandManager* GetSimulationIslandManager() const
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
btCollisionWorld* GetCollisionWorld()
|
||||
{
|
||||
return this;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DISCRETE_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
<<<<<<< .working
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||
@@ -43,4 +44,50 @@ class btDynamicsWorld : public CollisionWorld
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DYNAMICS_WORLD_H
|
||||
#endif //BT_DYNAMICS_WORLD_H=======
|
||||
/*
|
||||
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 BT_DYNAMICS_WORLD_H
|
||||
#define BT_DYNAMICS_WORLD_H
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionWorld.h"
|
||||
class btTypedConstraint;
|
||||
|
||||
///btDynamicsWorld is the baseclass for several dynamics implementation, basic, discrete, parallel, and continuous
|
||||
class btDynamicsWorld : public btCollisionWorld
|
||||
{
|
||||
public:
|
||||
|
||||
btDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache)
|
||||
:btCollisionWorld(dispatcher,pairCache)
|
||||
{
|
||||
|
||||
}
|
||||
virtual ~btDynamicsWorld()
|
||||
{
|
||||
}
|
||||
|
||||
///stepSimulation proceeds the simulation over timeStep units
|
||||
virtual void stepSimulation( float timeStep) = 0;
|
||||
|
||||
|
||||
virtual void addConstraint(btTypedConstraint* constraint) {};
|
||||
|
||||
virtual void removeConstraint(btTypedConstraint* constraint) {};
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DYNAMICS_WORLD_H>>>>>>> .merge-right.r324
|
||||
|
||||
@@ -16,16 +16,16 @@ subject to the following restrictions:
|
||||
#ifndef MASS_PROPS_H
|
||||
#define MASS_PROPS_H
|
||||
|
||||
#include <LinearMath/SimdVector3.h>
|
||||
#include <LinearMath/btVector3.h>
|
||||
|
||||
struct MassProps {
|
||||
MassProps(float mass,const SimdVector3& inertiaLocal):
|
||||
struct btMassProps {
|
||||
btMassProps(float mass,const btVector3& inertiaLocal):
|
||||
m_mass(mass),
|
||||
m_inertiaLocal(inertiaLocal)
|
||||
{
|
||||
}
|
||||
float m_mass;
|
||||
SimdVector3 m_inertiaLocal;
|
||||
btVector3 m_inertiaLocal;
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -16,14 +16,14 @@ subject to the following restrictions:
|
||||
#include "btRigidBody.h"
|
||||
#include "btMassProps.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "LinearMath/GenMinMax.h"
|
||||
#include <LinearMath/SimdTransformUtil.h>
|
||||
#include "LinearMath/btMinMax.h"
|
||||
#include <LinearMath/btTransformUtil.h>
|
||||
|
||||
float gLinearAirDamping = 1.f;
|
||||
|
||||
static int uniqueId = 0;
|
||||
|
||||
RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdScalar angularDamping,SimdScalar friction,SimdScalar restitution)
|
||||
btRigidBody::btRigidBody( const btMassProps& massProps,btScalar linearDamping,btScalar angularDamping,btScalar friction,btScalar restitution)
|
||||
:
|
||||
m_gravity(0.0f, 0.0f, 0.0f),
|
||||
m_totalForce(0.0f, 0.0f, 0.0f),
|
||||
@@ -37,7 +37,7 @@ RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdSc
|
||||
m_frictionSolverType(0)
|
||||
{
|
||||
|
||||
//moved to CollisionObject
|
||||
//moved to btCollisionObject
|
||||
m_friction = friction;
|
||||
m_restitution = restitution;
|
||||
|
||||
@@ -51,25 +51,25 @@ RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdSc
|
||||
}
|
||||
|
||||
|
||||
void RigidBody::setLinearVelocity(const SimdVector3& lin_vel)
|
||||
void btRigidBody::setLinearVelocity(const btVector3& lin_vel)
|
||||
{
|
||||
|
||||
m_linearVelocity = lin_vel;
|
||||
}
|
||||
|
||||
|
||||
void RigidBody::predictIntegratedTransform(SimdScalar timeStep,SimdTransform& predictedTransform) const
|
||||
void btRigidBody::predictIntegratedTransform(btScalar timeStep,btTransform& predictedTransform) const
|
||||
{
|
||||
SimdTransformUtil::IntegrateTransform(m_worldTransform,m_linearVelocity,m_angularVelocity,timeStep,predictedTransform);
|
||||
btTransformUtil::IntegrateTransform(m_worldTransform,m_linearVelocity,m_angularVelocity,timeStep,predictedTransform);
|
||||
}
|
||||
|
||||
void RigidBody::saveKinematicState(SimdScalar timeStep)
|
||||
void btRigidBody::saveKinematicState(btScalar timeStep)
|
||||
{
|
||||
|
||||
if (m_kinematicTimeStep)
|
||||
{
|
||||
SimdVector3 linVel,angVel;
|
||||
SimdTransformUtil::CalculateVelocity(m_interpolationWorldTransform,m_worldTransform,m_kinematicTimeStep,m_linearVelocity,m_angularVelocity);
|
||||
btVector3 linVel,angVel;
|
||||
btTransformUtil::CalculateVelocity(m_interpolationWorldTransform,m_worldTransform,m_kinematicTimeStep,m_linearVelocity,m_angularVelocity);
|
||||
//printf("angular = %f %f %f\n",m_angularVelocity.getX(),m_angularVelocity.getY(),m_angularVelocity.getZ());
|
||||
}
|
||||
|
||||
@@ -79,7 +79,7 @@ void RigidBody::saveKinematicState(SimdScalar timeStep)
|
||||
m_kinematicTimeStep = timeStep;
|
||||
}
|
||||
|
||||
void RigidBody::getAabb(SimdVector3& aabbMin,SimdVector3& aabbMax) const
|
||||
void btRigidBody::getAabb(btVector3& aabbMin,btVector3& aabbMax) const
|
||||
{
|
||||
GetCollisionShape()->GetAabb(m_worldTransform,aabbMin,aabbMax);
|
||||
}
|
||||
@@ -87,7 +87,7 @@ void RigidBody::getAabb(SimdVector3& aabbMin,SimdVector3& aabbMax) const
|
||||
|
||||
|
||||
|
||||
void RigidBody::setGravity(const SimdVector3& acceleration)
|
||||
void btRigidBody::setGravity(const btVector3& acceleration)
|
||||
{
|
||||
if (m_inverseMass != 0.0f)
|
||||
{
|
||||
@@ -100,7 +100,7 @@ void RigidBody::setGravity(const SimdVector3& acceleration)
|
||||
|
||||
|
||||
|
||||
void RigidBody::setDamping(SimdScalar lin_damping, SimdScalar ang_damping)
|
||||
void btRigidBody::setDamping(btScalar lin_damping, btScalar ang_damping)
|
||||
{
|
||||
m_linearDamping = GEN_clamped(lin_damping, 0.0f, 1.0f);
|
||||
m_angularDamping = GEN_clamped(ang_damping, 0.0f, 1.0f);
|
||||
@@ -111,7 +111,7 @@ void RigidBody::setDamping(SimdScalar lin_damping, SimdScalar ang_damping)
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
void RigidBody::applyForces(SimdScalar step)
|
||||
void btRigidBody::applyForces(btScalar step)
|
||||
{
|
||||
if (IsStatic())
|
||||
return;
|
||||
@@ -130,7 +130,7 @@ void RigidBody::applyForces(SimdScalar step)
|
||||
float dampVel = 0.005f;
|
||||
if (speed > dampVel)
|
||||
{
|
||||
SimdVector3 dir = m_linearVelocity.normalized();
|
||||
btVector3 dir = m_linearVelocity.normalized();
|
||||
m_linearVelocity -= dir * dampVel;
|
||||
} else
|
||||
{
|
||||
@@ -144,7 +144,7 @@ void RigidBody::applyForces(SimdScalar step)
|
||||
float angDampVel = 0.005f;
|
||||
if (angSpeed > angDampVel)
|
||||
{
|
||||
SimdVector3 dir = m_angularVelocity.normalized();
|
||||
btVector3 dir = m_angularVelocity.normalized();
|
||||
m_angularVelocity -= dir * angDampVel;
|
||||
} else
|
||||
{
|
||||
@@ -155,17 +155,17 @@ void RigidBody::applyForces(SimdScalar step)
|
||||
|
||||
}
|
||||
|
||||
void RigidBody::proceedToTransform(const SimdTransform& newTrans)
|
||||
void btRigidBody::proceedToTransform(const btTransform& newTrans)
|
||||
{
|
||||
setCenterOfMassTransform( newTrans );
|
||||
}
|
||||
|
||||
|
||||
void RigidBody::setMassProps(SimdScalar mass, const SimdVector3& inertia)
|
||||
void btRigidBody::setMassProps(btScalar mass, const btVector3& inertia)
|
||||
{
|
||||
if (mass == 0.f)
|
||||
{
|
||||
m_collisionFlags = CollisionObject::isStatic;
|
||||
m_collisionFlags = btCollisionObject::isStatic;
|
||||
m_inverseMass = 0.f;
|
||||
} else
|
||||
{
|
||||
@@ -182,13 +182,13 @@ void RigidBody::setMassProps(SimdScalar mass, const SimdVector3& inertia)
|
||||
|
||||
|
||||
|
||||
void RigidBody::updateInertiaTensor()
|
||||
void btRigidBody::updateInertiaTensor()
|
||||
{
|
||||
m_invInertiaTensorWorld = m_worldTransform.getBasis().scaled(m_invInertiaLocal) * m_worldTransform.getBasis().transpose();
|
||||
}
|
||||
|
||||
|
||||
void RigidBody::integrateVelocities(SimdScalar step)
|
||||
void btRigidBody::integrateVelocities(btScalar step)
|
||||
{
|
||||
if (IsStatic())
|
||||
return;
|
||||
@@ -207,15 +207,15 @@ void RigidBody::integrateVelocities(SimdScalar step)
|
||||
clearForces();
|
||||
}
|
||||
|
||||
SimdQuaternion RigidBody::getOrientation() const
|
||||
btQuaternion btRigidBody::getOrientation() const
|
||||
{
|
||||
SimdQuaternion orn;
|
||||
btQuaternion orn;
|
||||
m_worldTransform.getBasis().getRotation(orn);
|
||||
return orn;
|
||||
}
|
||||
|
||||
|
||||
void RigidBody::setCenterOfMassTransform(const SimdTransform& xform)
|
||||
void btRigidBody::setCenterOfMassTransform(const btTransform& xform)
|
||||
{
|
||||
m_worldTransform = xform;
|
||||
updateInertiaTensor();
|
||||
|
||||
@@ -17,25 +17,29 @@ subject to the following restrictions:
|
||||
#define RIGIDBODY_H
|
||||
|
||||
#include <vector>
|
||||
#include <LinearMath/SimdPoint3.h>
|
||||
#include <LinearMath/SimdTransform.h>
|
||||
#include <LinearMath/btPoint3.h>
|
||||
#include <LinearMath/btTransform.h>
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
|
||||
|
||||
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||
|
||||
class CollisionShape;
|
||||
struct MassProps;
|
||||
typedef SimdScalar dMatrix3[4*3];
|
||||
class btCollisionShape;
|
||||
struct btMassProps;
|
||||
typedef btScalar dMatrix3[4*3];
|
||||
|
||||
extern float gLinearAirDamping;
|
||||
extern bool gUseEpa;
|
||||
|
||||
extern float gDeactivationTime;
|
||||
extern bool gDisableDeactivation;
|
||||
extern float gLinearSleepingTreshold;
|
||||
extern float gAngularSleepingTreshold;
|
||||
|
||||
|
||||
/// RigidBody class for RigidBody Dynamics
|
||||
/// btRigidBody class for btRigidBody Dynamics
|
||||
///
|
||||
class RigidBody : public CollisionObject
|
||||
class btRigidBody : public btCollisionObject
|
||||
{
|
||||
|
||||
SimdMatrix3x3 m_invInertiaTensorWorld;
|
||||
@@ -57,81 +61,81 @@ class RigidBody : public CollisionObject
|
||||
|
||||
public:
|
||||
|
||||
RigidBody(const MassProps& massProps,SimdScalar linearDamping,SimdScalar angularDamping,SimdScalar friction,SimdScalar restitution);
|
||||
btRigidBody(const btMassProps& massProps,btScalar linearDamping=0.f,btScalar angularDamping=0.f,btScalar friction=0.5f,btScalar restitution=0.f);
|
||||
|
||||
void proceedToTransform(const SimdTransform& newTrans);
|
||||
void proceedToTransform(const btTransform& newTrans);
|
||||
|
||||
|
||||
/// continuous collision detection needs prediction
|
||||
void predictIntegratedTransform(SimdScalar step, SimdTransform& predictedTransform) const;
|
||||
void predictIntegratedTransform(btScalar step, btTransform& predictedTransform) const;
|
||||
|
||||
void saveKinematicState(SimdScalar step);
|
||||
void saveKinematicState(btScalar step);
|
||||
|
||||
|
||||
void applyForces(SimdScalar step);
|
||||
void applyForces(btScalar step);
|
||||
|
||||
void setGravity(const SimdVector3& acceleration);
|
||||
void setGravity(const btVector3& acceleration);
|
||||
|
||||
void setDamping(SimdScalar lin_damping, SimdScalar ang_damping);
|
||||
void setDamping(btScalar lin_damping, btScalar ang_damping);
|
||||
|
||||
inline const CollisionShape* GetCollisionShape() const {
|
||||
inline const btCollisionShape* GetCollisionShape() const {
|
||||
return m_collisionShape;
|
||||
}
|
||||
|
||||
inline CollisionShape* GetCollisionShape() {
|
||||
inline btCollisionShape* GetCollisionShape() {
|
||||
return m_collisionShape;
|
||||
}
|
||||
|
||||
void setMassProps(SimdScalar mass, const SimdVector3& inertia);
|
||||
void setMassProps(btScalar mass, const btVector3& inertia);
|
||||
|
||||
SimdScalar getInvMass() const { return m_inverseMass; }
|
||||
const SimdMatrix3x3& getInvInertiaTensorWorld() const {
|
||||
btScalar getInvMass() const { return m_inverseMass; }
|
||||
const btMatrix3x3& getInvInertiaTensorWorld() const {
|
||||
return m_invInertiaTensorWorld;
|
||||
}
|
||||
|
||||
void integrateVelocities(SimdScalar step);
|
||||
void integrateVelocities(btScalar step);
|
||||
|
||||
void setCenterOfMassTransform(const SimdTransform& xform);
|
||||
void setCenterOfMassTransform(const btTransform& xform);
|
||||
|
||||
void applyCentralForce(const SimdVector3& force)
|
||||
void applyCentralForce(const btVector3& force)
|
||||
{
|
||||
m_totalForce += force;
|
||||
}
|
||||
|
||||
const SimdVector3& getInvInertiaDiagLocal()
|
||||
const btVector3& getInvInertiaDiagLocal()
|
||||
{
|
||||
return m_invInertiaLocal;
|
||||
};
|
||||
|
||||
void setInvInertiaDiagLocal(const SimdVector3& diagInvInertia)
|
||||
void setInvInertiaDiagLocal(const btVector3& diagInvInertia)
|
||||
{
|
||||
m_invInertiaLocal = diagInvInertia;
|
||||
}
|
||||
|
||||
void applyTorque(const SimdVector3& torque)
|
||||
void applyTorque(const btVector3& torque)
|
||||
{
|
||||
m_totalTorque += torque;
|
||||
}
|
||||
|
||||
void applyForce(const SimdVector3& force, const SimdVector3& rel_pos)
|
||||
void applyForce(const btVector3& force, const btVector3& rel_pos)
|
||||
{
|
||||
applyCentralForce(force);
|
||||
applyTorque(rel_pos.cross(force));
|
||||
}
|
||||
|
||||
void applyCentralImpulse(const SimdVector3& impulse)
|
||||
void applyCentralImpulse(const btVector3& impulse)
|
||||
{
|
||||
m_linearVelocity += impulse * m_inverseMass;
|
||||
}
|
||||
|
||||
void applyTorqueImpulse(const SimdVector3& torque)
|
||||
void applyTorqueImpulse(const btVector3& torque)
|
||||
{
|
||||
if (!IsStatic())
|
||||
m_angularVelocity += m_invInertiaTensorWorld * torque;
|
||||
|
||||
}
|
||||
|
||||
void applyImpulse(const SimdVector3& impulse, const SimdVector3& rel_pos)
|
||||
void applyImpulse(const btVector3& impulse, const btVector3& rel_pos)
|
||||
{
|
||||
if (m_inverseMass != 0.f)
|
||||
{
|
||||
@@ -148,31 +152,31 @@ public:
|
||||
|
||||
void updateInertiaTensor();
|
||||
|
||||
const SimdPoint3& getCenterOfMassPosition() const {
|
||||
const btPoint3& getCenterOfMassPosition() const {
|
||||
return m_worldTransform.getOrigin();
|
||||
}
|
||||
SimdQuaternion getOrientation() const;
|
||||
btQuaternion getOrientation() const;
|
||||
|
||||
const SimdTransform& getCenterOfMassTransform() const {
|
||||
const btTransform& getCenterOfMassTransform() const {
|
||||
return m_worldTransform;
|
||||
}
|
||||
const SimdVector3& getLinearVelocity() const {
|
||||
const btVector3& getLinearVelocity() const {
|
||||
return m_linearVelocity;
|
||||
}
|
||||
const SimdVector3& getAngularVelocity() const {
|
||||
const btVector3& getAngularVelocity() const {
|
||||
return m_angularVelocity;
|
||||
}
|
||||
|
||||
|
||||
void setLinearVelocity(const SimdVector3& lin_vel);
|
||||
void setAngularVelocity(const SimdVector3& ang_vel) {
|
||||
void setLinearVelocity(const btVector3& lin_vel);
|
||||
void setAngularVelocity(const btVector3& ang_vel) {
|
||||
if (!IsStatic())
|
||||
{
|
||||
m_angularVelocity = ang_vel;
|
||||
}
|
||||
}
|
||||
|
||||
SimdVector3 getVelocityInLocalPoint(const SimdVector3& rel_pos) const
|
||||
btVector3 getVelocityInLocalPoint(const btVector3& rel_pos) const
|
||||
{
|
||||
//we also calculate lin/ang velocity for kinematic objects
|
||||
return m_linearVelocity + m_angularVelocity.cross(rel_pos);
|
||||
@@ -181,52 +185,84 @@ public:
|
||||
// return (m_worldTransform(rel_pos) - m_interpolationWorldTransform(rel_pos)) / m_kinematicTimeStep;
|
||||
}
|
||||
|
||||
void translate(const SimdVector3& v)
|
||||
void translate(const btVector3& v)
|
||||
{
|
||||
m_worldTransform.getOrigin() += v;
|
||||
}
|
||||
|
||||
|
||||
void getAabb(SimdVector3& aabbMin,SimdVector3& aabbMax) const;
|
||||
void getAabb(btVector3& aabbMin,btVector3& aabbMax) const;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
inline float ComputeImpulseDenominator(const SimdPoint3& pos, const SimdVector3& normal) const
|
||||
inline float ComputeImpulseDenominator(const btPoint3& pos, const btVector3& normal) const
|
||||
{
|
||||
SimdVector3 r0 = pos - getCenterOfMassPosition();
|
||||
btVector3 r0 = pos - getCenterOfMassPosition();
|
||||
|
||||
SimdVector3 c0 = (r0).cross(normal);
|
||||
btVector3 c0 = (r0).cross(normal);
|
||||
|
||||
SimdVector3 vec = (c0 * getInvInertiaTensorWorld()).cross(r0);
|
||||
btVector3 vec = (c0 * getInvInertiaTensorWorld()).cross(r0);
|
||||
|
||||
return m_inverseMass + normal.dot(vec);
|
||||
|
||||
}
|
||||
|
||||
inline float ComputeAngularImpulseDenominator(const SimdVector3& axis) const
|
||||
inline float ComputeAngularImpulseDenominator(const btVector3& axis) const
|
||||
{
|
||||
SimdVector3 vec = axis * getInvInertiaTensorWorld();
|
||||
btVector3 vec = axis * getInvInertiaTensorWorld();
|
||||
return axis.dot(vec);
|
||||
}
|
||||
|
||||
inline void updateDeactivation(float timeStep)
|
||||
{
|
||||
if ( (GetActivationState() == ISLAND_SLEEPING) || (GetActivationState() == DISABLE_DEACTIVATION))
|
||||
return;
|
||||
|
||||
if ((getLinearVelocity().length2() < gLinearSleepingTreshold*gLinearSleepingTreshold) &&
|
||||
(getAngularVelocity().length2() < gAngularSleepingTreshold*gAngularSleepingTreshold))
|
||||
{
|
||||
m_deactivationTime += timeStep;
|
||||
} else
|
||||
{
|
||||
m_deactivationTime=0.f;
|
||||
SetActivationState(0);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
inline bool wantsSleeping()
|
||||
{
|
||||
|
||||
if (GetActivationState() == DISABLE_DEACTIVATION)
|
||||
return false;
|
||||
|
||||
//disable deactivation
|
||||
if (gDisableDeactivation || (gDeactivationTime == 0.f))
|
||||
return false;
|
||||
|
||||
if ( (GetActivationState() == ISLAND_SLEEPING) || (GetActivationState() == WANTS_DEACTIVATION))
|
||||
return true;
|
||||
|
||||
if (m_deactivationTime> gDeactivationTime)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
|
||||
|
||||
public:
|
||||
const BroadphaseProxy* GetBroadphaseProxy() const
|
||||
const btBroadphaseProxy* GetBroadphaseProxy() const
|
||||
{
|
||||
return m_broadphaseProxy;
|
||||
}
|
||||
BroadphaseProxy* GetBroadphaseProxy()
|
||||
btBroadphaseProxy* GetBroadphaseProxy()
|
||||
{
|
||||
return m_broadphaseProxy;
|
||||
}
|
||||
void SetBroadphaseProxy(BroadphaseProxy* broadphaseProxy)
|
||||
void SetBroadphaseProxy(btBroadphaseProxy* broadphaseProxy)
|
||||
{
|
||||
m_broadphaseProxy = broadphaseProxy;
|
||||
}
|
||||
@@ -235,18 +271,6 @@ public:
|
||||
int m_contactSolverType;
|
||||
int m_frictionSolverType;
|
||||
|
||||
/*
|
||||
//unused
|
||||
/// for ode solver-binding
|
||||
dMatrix3 m_R;//temp
|
||||
dMatrix3 m_I;
|
||||
dMatrix3 m_invI;
|
||||
|
||||
int m_odeTag;
|
||||
|
||||
SimdVector3 m_tacc;//temp
|
||||
SimdVector3 m_facc;
|
||||
*/
|
||||
|
||||
|
||||
int m_debugBodyId;
|
||||
|
||||
@@ -117,4 +117,124 @@ void btSimpleDynamicsWorld::predictUnconstraintMotion(float timeStep)
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}=======
|
||||
|
||||
#include "btSimpleDynamicsWorld.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btSimpleBroadphase.h"
|
||||
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
|
||||
|
||||
btSimpleDynamicsWorld::btSimpleDynamicsWorld()
|
||||
:btDynamicsWorld(new btCollisionDispatcher(),new btSimpleBroadphase()),
|
||||
m_constraintSolver(new btSequentialImpulseConstraintSolver)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
btSimpleDynamicsWorld::btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
|
||||
:btDynamicsWorld(dispatcher,pairCache),
|
||||
m_constraintSolver(constraintSolver)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
btSimpleDynamicsWorld::~btSimpleDynamicsWorld()
|
||||
{
|
||||
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)
|
||||
{
|
||||
///apply gravity, predict motion
|
||||
predictUnconstraintMotion(timeStep);
|
||||
|
||||
///perform collision detection
|
||||
PerformDiscreteCollisionDetection();
|
||||
|
||||
///solve contact constraints
|
||||
btPersistentManifold** manifoldPtr = ((btCollisionDispatcher*)m_dispatcher1)->getInternalManifoldPointer();
|
||||
int numManifolds = m_dispatcher1->GetNumManifolds();
|
||||
btContactSolverInfo infoGlobal;
|
||||
infoGlobal.m_timeStep = timeStep;
|
||||
btIDebugDraw* debugDrawer=0;
|
||||
m_constraintSolver->SolveGroup(manifoldPtr, numManifolds,infoGlobal,debugDrawer);
|
||||
|
||||
///integrate transforms
|
||||
integrateTransforms(timeStep);
|
||||
|
||||
updateAabbs();
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::updateAabbs()
|
||||
{
|
||||
btTransform predictedTrans;
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
btPoint3 minAabb,maxAabb;
|
||||
colObj->m_collisionShape->GetAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_pairCache;
|
||||
bp->SetAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void btSimpleDynamicsWorld::integrateTransforms(float timeStep)
|
||||
{
|
||||
btTransform predictedTrans;
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->predictIntegratedTransform(timeStep, predictedTrans);
|
||||
body->proceedToTransform( predictedTrans);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::predictUnconstraintMotion(float timeStep)
|
||||
{
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->applyForces( timeStep);
|
||||
body->integrateVelocities( timeStep);
|
||||
body->predictIntegratedTransform(timeStep,body->m_interpolationWorldTransform);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -52,4 +52,59 @@ public:
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_SIMPLE_DYNAMICS_WORLD_H
|
||||
#endif //BT_SIMPLE_DYNAMICS_WORLD_H=======
|
||||
/*
|
||||
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 BT_SIMPLE_DYNAMICS_WORLD_H
|
||||
#define BT_SIMPLE_DYNAMICS_WORLD_H
|
||||
|
||||
#include "btDynamicsWorld.h"
|
||||
|
||||
class btDispatcher;
|
||||
class btOverlappingPairCache;
|
||||
class btConstraintSolver;
|
||||
|
||||
///btSimpleDynamicsWorld demonstrates very basic usage of Bullet rigid body dynamics
|
||||
///It can be used for basic simulations, and as a starting point for porting Bullet
|
||||
///btSimpleDynamicsWorld lacks object deactivation, island management and other concepts.
|
||||
///For more complicated simulations, btDiscreteDynamicsWorld and btContinuousDynamicsWorld are recommended
|
||||
///those classes replace the obsolete CcdPhysicsEnvironment/CcdPhysicsController
|
||||
class btSimpleDynamicsWorld : public btDynamicsWorld
|
||||
{
|
||||
protected:
|
||||
|
||||
btConstraintSolver* m_constraintSolver;
|
||||
|
||||
void predictUnconstraintMotion(float timeStep);
|
||||
|
||||
void integrateTransforms(float timeStep);
|
||||
|
||||
void updateAabbs();
|
||||
|
||||
public:
|
||||
|
||||
|
||||
btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver);
|
||||
|
||||
btSimpleDynamicsWorld();
|
||||
|
||||
virtual ~btSimpleDynamicsWorld();
|
||||
|
||||
virtual void stepSimulation( float timeStep);
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_SIMPLE_DYNAMICS_WORLD_H
|
||||
|
||||
Reference in New Issue
Block a user