add bullet
This commit is contained in:
46
libs/bullet/BulletDynamics/Dynamics/btActionInterface.h
Normal file
46
libs/bullet/BulletDynamics/Dynamics/btActionInterface.h
Normal file
@ -0,0 +1,46 @@
|
||||
/*
|
||||
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_ACTION_INTERFACE_H
|
||||
#define _BT_ACTION_INTERFACE_H
|
||||
|
||||
class btIDebugDraw;
|
||||
class btCollisionWorld;
|
||||
|
||||
#include "LinearMath/btScalar.h"
|
||||
#include "btRigidBody.h"
|
||||
|
||||
///Basic interface to allow actions such as vehicles and characters to be updated inside a btDynamicsWorld
|
||||
class btActionInterface
|
||||
{
|
||||
protected:
|
||||
|
||||
static btRigidBody& getFixedBody();
|
||||
|
||||
|
||||
public:
|
||||
|
||||
virtual ~btActionInterface()
|
||||
{
|
||||
}
|
||||
|
||||
virtual void updateAction( btCollisionWorld* collisionWorld, btScalar deltaTimeStep)=0;
|
||||
|
||||
virtual void debugDraw(btIDebugDraw* debugDrawer) = 0;
|
||||
|
||||
};
|
||||
|
||||
#endif //_BT_ACTION_INTERFACE_H
|
||||
|
@ -0,0 +1,196 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2007 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 "btContinuousDynamicsWorld.h"
|
||||
#include "LinearMath/btQuickprof.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"
|
||||
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
btContinuousDynamicsWorld::btContinuousDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration)
|
||||
:btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration)
|
||||
{
|
||||
}
|
||||
|
||||
btContinuousDynamicsWorld::~btContinuousDynamicsWorld()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void btContinuousDynamicsWorld::internalSingleStepSimulation( btScalar timeStep)
|
||||
{
|
||||
|
||||
startProfiling(timeStep);
|
||||
|
||||
if(0 != m_internalPreTickCallback) {
|
||||
(*m_internalPreTickCallback)(this, timeStep);
|
||||
}
|
||||
|
||||
|
||||
///update aabbs information
|
||||
updateAabbs();
|
||||
//static int frame=0;
|
||||
// printf("frame %d\n",frame++);
|
||||
|
||||
///apply gravity, predict motion
|
||||
predictUnconstraintMotion(timeStep);
|
||||
|
||||
btDispatcherInfo& dispatchInfo = getDispatchInfo();
|
||||
|
||||
dispatchInfo.m_timeStep = timeStep;
|
||||
dispatchInfo.m_stepCount = 0;
|
||||
dispatchInfo.m_debugDraw = getDebugDrawer();
|
||||
|
||||
///perform collision detection
|
||||
performDiscreteCollisionDetection();
|
||||
|
||||
calculateSimulationIslands();
|
||||
|
||||
|
||||
getSolverInfo().m_timeStep = timeStep;
|
||||
|
||||
|
||||
|
||||
///solve contact and other joint constraints
|
||||
solveConstraints(getSolverInfo());
|
||||
|
||||
///CallbackTriggers();
|
||||
calculateTimeOfImpacts(timeStep);
|
||||
|
||||
btScalar toi = dispatchInfo.m_timeOfImpact;
|
||||
// if (toi < 1.f)
|
||||
// printf("toi = %f\n",toi);
|
||||
if (toi < 0.f)
|
||||
printf("toi = %f\n",toi);
|
||||
|
||||
|
||||
///integrate transforms
|
||||
integrateTransforms(timeStep * toi);
|
||||
|
||||
///update vehicle simulation
|
||||
updateActions(timeStep);
|
||||
|
||||
updateActivationState( timeStep );
|
||||
|
||||
if(0 != m_internalTickCallback) {
|
||||
(*m_internalTickCallback)(this, timeStep);
|
||||
}
|
||||
}
|
||||
|
||||
void btContinuousDynamicsWorld::calculateTimeOfImpacts(btScalar timeStep)
|
||||
{
|
||||
///these should be 'temporal' aabbs!
|
||||
updateTemporalAabbs(timeStep);
|
||||
|
||||
///'toi' is the global smallest time of impact. However, we just calculate the time of impact for each object individually.
|
||||
///so we handle the case moving versus static properly, and we cheat for moving versus moving
|
||||
btScalar toi = 1.f;
|
||||
|
||||
|
||||
btDispatcherInfo& dispatchInfo = getDispatchInfo();
|
||||
dispatchInfo.m_timeStep = timeStep;
|
||||
dispatchInfo.m_timeOfImpact = 1.f;
|
||||
dispatchInfo.m_stepCount = 0;
|
||||
dispatchInfo.m_dispatchFunc = btDispatcherInfo::DISPATCH_CONTINUOUS;
|
||||
|
||||
///calculate time of impact for overlapping pairs
|
||||
|
||||
|
||||
btDispatcher* dispatcher = getDispatcher();
|
||||
if (dispatcher)
|
||||
dispatcher->dispatchAllCollisionPairs(m_broadphasePairCache->getOverlappingPairCache(),dispatchInfo,m_dispatcher1);
|
||||
|
||||
toi = dispatchInfo.m_timeOfImpact;
|
||||
|
||||
dispatchInfo.m_dispatchFunc = btDispatcherInfo::DISPATCH_DISCRETE;
|
||||
|
||||
}
|
||||
|
||||
void btContinuousDynamicsWorld::updateTemporalAabbs(btScalar timeStep)
|
||||
{
|
||||
|
||||
btVector3 temporalAabbMin,temporalAabbMax;
|
||||
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
body->getCollisionShape()->getAabb(m_collisionObjects[i]->getWorldTransform(),temporalAabbMin,temporalAabbMax);
|
||||
const btVector3& linvel = body->getLinearVelocity();
|
||||
|
||||
//make the AABB temporal
|
||||
btScalar temporalAabbMaxx = temporalAabbMax.getX();
|
||||
btScalar temporalAabbMaxy = temporalAabbMax.getY();
|
||||
btScalar temporalAabbMaxz = temporalAabbMax.getZ();
|
||||
btScalar temporalAabbMinx = temporalAabbMin.getX();
|
||||
btScalar temporalAabbMiny = temporalAabbMin.getY();
|
||||
btScalar temporalAabbMinz = temporalAabbMin.getZ();
|
||||
|
||||
// add linear motion
|
||||
btVector3 linMotion = linvel*timeStep;
|
||||
|
||||
if (linMotion.x() > 0.f)
|
||||
temporalAabbMaxx += linMotion.x();
|
||||
else
|
||||
temporalAabbMinx += linMotion.x();
|
||||
if (linMotion.y() > 0.f)
|
||||
temporalAabbMaxy += linMotion.y();
|
||||
else
|
||||
temporalAabbMiny += linMotion.y();
|
||||
if (linMotion.z() > 0.f)
|
||||
temporalAabbMaxz += linMotion.z();
|
||||
else
|
||||
temporalAabbMinz += linMotion.z();
|
||||
|
||||
//add conservative angular motion
|
||||
btScalar angularMotion(0);// = angvel.length() * GetAngularMotionDisc() * timeStep;
|
||||
btVector3 angularMotion3d(angularMotion,angularMotion,angularMotion);
|
||||
temporalAabbMin = btVector3(temporalAabbMinx,temporalAabbMiny,temporalAabbMinz);
|
||||
temporalAabbMax = btVector3(temporalAabbMaxx,temporalAabbMaxy,temporalAabbMaxz);
|
||||
|
||||
temporalAabbMin -= angularMotion3d;
|
||||
temporalAabbMax += angularMotion3d;
|
||||
|
||||
m_broadphasePairCache->setAabb(body->getBroadphaseHandle(),temporalAabbMin,temporalAabbMax,m_dispatcher1);
|
||||
}
|
||||
}
|
||||
|
||||
//update aabb (of all moved objects)
|
||||
|
||||
m_broadphasePairCache->calculateOverlappingPairs(m_dispatcher1);
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -0,0 +1,46 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2007 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_CONTINUOUS_DYNAMICS_WORLD_H
|
||||
#define BT_CONTINUOUS_DYNAMICS_WORLD_H
|
||||
|
||||
#include "btDiscreteDynamicsWorld.h"
|
||||
|
||||
///btContinuousDynamicsWorld adds optional (per object) continuous collision detection for fast moving objects to the btDiscreteDynamicsWorld.
|
||||
///This copes with fast moving objects that otherwise would tunnel/miss collisions.
|
||||
///Under construction, don't use yet! Please use btDiscreteDynamicsWorld instead.
|
||||
class btContinuousDynamicsWorld : public btDiscreteDynamicsWorld
|
||||
{
|
||||
|
||||
void updateTemporalAabbs(btScalar timeStep);
|
||||
|
||||
public:
|
||||
|
||||
btContinuousDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration);
|
||||
virtual ~btContinuousDynamicsWorld();
|
||||
|
||||
///time stepping with calculation of time of impact for selected fast moving objects
|
||||
virtual void internalSingleStepSimulation( btScalar timeStep);
|
||||
|
||||
virtual void calculateTimeOfImpacts(btScalar timeStep);
|
||||
|
||||
virtual btDynamicsWorldType getWorldType() const
|
||||
{
|
||||
return BT_CONTINUOUS_DYNAMICS_WORLD;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_CONTINUOUS_DYNAMICS_WORLD_H
|
1161
libs/bullet/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
Normal file
1161
libs/bullet/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
Normal file
File diff suppressed because it is too large
Load Diff
198
libs/bullet/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
Normal file
198
libs/bullet/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
Normal file
@ -0,0 +1,198 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org
|
||||
|
||||
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;
|
||||
class btActionInterface;
|
||||
|
||||
class btIDebugDraw;
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
|
||||
|
||||
///btDiscreteDynamicsWorld provides discrete rigid body simulation
|
||||
///those classes replace the obsolete CcdPhysicsEnvironment/CcdPhysicsController
|
||||
class btDiscreteDynamicsWorld : public btDynamicsWorld
|
||||
{
|
||||
protected:
|
||||
|
||||
btConstraintSolver* m_constraintSolver;
|
||||
|
||||
btSimulationIslandManager* m_islandManager;
|
||||
|
||||
btAlignedObjectArray<btTypedConstraint*> m_constraints;
|
||||
|
||||
btAlignedObjectArray<btRigidBody*> m_nonStaticRigidBodies;
|
||||
|
||||
btVector3 m_gravity;
|
||||
|
||||
//for variable timesteps
|
||||
btScalar m_localTime;
|
||||
//for variable timesteps
|
||||
|
||||
bool m_ownsIslandManager;
|
||||
bool m_ownsConstraintSolver;
|
||||
bool m_synchronizeAllMotionStates;
|
||||
|
||||
btAlignedObjectArray<btActionInterface*> m_actions;
|
||||
|
||||
int m_profileTimings;
|
||||
|
||||
virtual void predictUnconstraintMotion(btScalar timeStep);
|
||||
|
||||
virtual void integrateTransforms(btScalar timeStep);
|
||||
|
||||
virtual void calculateSimulationIslands();
|
||||
|
||||
virtual void solveConstraints(btContactSolverInfo& solverInfo);
|
||||
|
||||
void updateActivationState(btScalar timeStep);
|
||||
|
||||
void updateActions(btScalar timeStep);
|
||||
|
||||
void startProfiling(btScalar timeStep);
|
||||
|
||||
virtual void internalSingleStepSimulation( btScalar timeStep);
|
||||
|
||||
|
||||
virtual void saveKinematicState(btScalar timeStep);
|
||||
|
||||
void serializeRigidBodies(btSerializer* serializer);
|
||||
|
||||
public:
|
||||
|
||||
|
||||
///this btDiscreteDynamicsWorld constructor gets created objects from the user, and will not delete those
|
||||
btDiscreteDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration);
|
||||
|
||||
virtual ~btDiscreteDynamicsWorld();
|
||||
|
||||
///if maxSubSteps > 0, it will interpolate motion between fixedTimeStep's
|
||||
virtual int stepSimulation( btScalar timeStep,int maxSubSteps=1, btScalar fixedTimeStep=btScalar(1.)/btScalar(60.));
|
||||
|
||||
|
||||
virtual void synchronizeMotionStates();
|
||||
|
||||
///this can be useful to synchronize a single rigid body -> graphics object
|
||||
void synchronizeSingleMotionState(btRigidBody* body);
|
||||
|
||||
virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false);
|
||||
|
||||
virtual void removeConstraint(btTypedConstraint* constraint);
|
||||
|
||||
virtual void addAction(btActionInterface*);
|
||||
|
||||
virtual void removeAction(btActionInterface*);
|
||||
|
||||
btSimulationIslandManager* getSimulationIslandManager()
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
const btSimulationIslandManager* getSimulationIslandManager() const
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
btCollisionWorld* getCollisionWorld()
|
||||
{
|
||||
return this;
|
||||
}
|
||||
|
||||
virtual void setGravity(const btVector3& gravity);
|
||||
|
||||
virtual btVector3 getGravity () const;
|
||||
|
||||
virtual void addCollisionObject(btCollisionObject* collisionObject,short int collisionFilterGroup=btBroadphaseProxy::StaticFilter,short int collisionFilterMask=btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
virtual void addRigidBody(btRigidBody* body);
|
||||
|
||||
virtual void addRigidBody(btRigidBody* body, short group, short mask);
|
||||
|
||||
virtual void removeRigidBody(btRigidBody* body);
|
||||
|
||||
///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject
|
||||
virtual void removeCollisionObject(btCollisionObject* collisionObject);
|
||||
|
||||
|
||||
void debugDrawConstraint(btTypedConstraint* constraint);
|
||||
|
||||
virtual void debugDrawWorld();
|
||||
|
||||
virtual void setConstraintSolver(btConstraintSolver* solver);
|
||||
|
||||
virtual btConstraintSolver* getConstraintSolver();
|
||||
|
||||
virtual int getNumConstraints() const;
|
||||
|
||||
virtual btTypedConstraint* getConstraint(int index) ;
|
||||
|
||||
virtual const btTypedConstraint* getConstraint(int index) const;
|
||||
|
||||
|
||||
virtual btDynamicsWorldType getWorldType() const
|
||||
{
|
||||
return BT_DISCRETE_DYNAMICS_WORLD;
|
||||
}
|
||||
|
||||
///the forces on each rigidbody is accumulating together with gravity. clear this after each timestep.
|
||||
virtual void clearForces();
|
||||
|
||||
///apply gravity, call this once per timestep
|
||||
virtual void applyGravity();
|
||||
|
||||
virtual void setNumTasks(int numTasks)
|
||||
{
|
||||
(void) numTasks;
|
||||
}
|
||||
|
||||
///obsolete, use updateActions instead
|
||||
virtual void updateVehicles(btScalar timeStep)
|
||||
{
|
||||
updateActions(timeStep);
|
||||
}
|
||||
|
||||
///obsolete, use addAction instead
|
||||
virtual void addVehicle(btActionInterface* vehicle);
|
||||
///obsolete, use removeAction instead
|
||||
virtual void removeVehicle(btActionInterface* vehicle);
|
||||
///obsolete, use addAction instead
|
||||
virtual void addCharacter(btActionInterface* character);
|
||||
///obsolete, use removeAction instead
|
||||
virtual void removeCharacter(btActionInterface* character);
|
||||
|
||||
void setSynchronizeAllMotionStates(bool synchronizeAll)
|
||||
{
|
||||
m_synchronizeAllMotionStates = synchronizeAll;
|
||||
}
|
||||
bool getSynchronizeAllMotionStates() const
|
||||
{
|
||||
return m_synchronizeAllMotionStates;
|
||||
}
|
||||
|
||||
///Preliminary serialization test for Bullet 2.76. Loading those files requires a separate parser (see Bullet/Demos/SerializeDemo)
|
||||
virtual void serialize(btSerializer* serializer);
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DISCRETE_DYNAMICS_WORLD_H
|
148
libs/bullet/BulletDynamics/Dynamics/btDynamicsWorld.h
Normal file
148
libs/bullet/BulletDynamics/Dynamics/btDynamicsWorld.h
Normal file
@ -0,0 +1,148 @@
|
||||
/*
|
||||
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"
|
||||
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
|
||||
|
||||
class btTypedConstraint;
|
||||
class btActionInterface;
|
||||
class btConstraintSolver;
|
||||
class btDynamicsWorld;
|
||||
|
||||
|
||||
/// Type for the callback for each tick
|
||||
typedef void (*btInternalTickCallback)(btDynamicsWorld *world, btScalar timeStep);
|
||||
|
||||
enum btDynamicsWorldType
|
||||
{
|
||||
BT_SIMPLE_DYNAMICS_WORLD=1,
|
||||
BT_DISCRETE_DYNAMICS_WORLD=2,
|
||||
BT_CONTINUOUS_DYNAMICS_WORLD=3
|
||||
};
|
||||
|
||||
///The btDynamicsWorld is the interface class for several dynamics implementation, basic, discrete, parallel, and continuous etc.
|
||||
class btDynamicsWorld : public btCollisionWorld
|
||||
{
|
||||
|
||||
protected:
|
||||
btInternalTickCallback m_internalTickCallback;
|
||||
btInternalTickCallback m_internalPreTickCallback;
|
||||
void* m_worldUserInfo;
|
||||
|
||||
btContactSolverInfo m_solverInfo;
|
||||
|
||||
public:
|
||||
|
||||
|
||||
btDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* broadphase,btCollisionConfiguration* collisionConfiguration)
|
||||
:btCollisionWorld(dispatcher,broadphase,collisionConfiguration), m_internalTickCallback(0),m_internalPreTickCallback(0), m_worldUserInfo(0)
|
||||
{
|
||||
}
|
||||
|
||||
virtual ~btDynamicsWorld()
|
||||
{
|
||||
}
|
||||
|
||||
///stepSimulation proceeds the simulation over 'timeStep', units in preferably in seconds.
|
||||
///By default, Bullet will subdivide the timestep in constant substeps of each 'fixedTimeStep'.
|
||||
///in order to keep the simulation real-time, the maximum number of substeps can be clamped to 'maxSubSteps'.
|
||||
///You can disable subdividing the timestep/substepping by passing maxSubSteps=0 as second argument to stepSimulation, but in that case you have to keep the timeStep constant.
|
||||
virtual int stepSimulation( btScalar timeStep,int maxSubSteps=1, btScalar fixedTimeStep=btScalar(1.)/btScalar(60.))=0;
|
||||
|
||||
virtual void debugDrawWorld() = 0;
|
||||
|
||||
virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false)
|
||||
{
|
||||
(void)constraint; (void)disableCollisionsBetweenLinkedBodies;
|
||||
}
|
||||
|
||||
virtual void removeConstraint(btTypedConstraint* constraint) {(void)constraint;}
|
||||
|
||||
virtual void addAction(btActionInterface* action) = 0;
|
||||
|
||||
virtual void removeAction(btActionInterface* action) = 0;
|
||||
|
||||
//once a rigidbody is added to the dynamics world, it will get this gravity assigned
|
||||
//existing rigidbodies in the world get gravity assigned too, during this method
|
||||
virtual void setGravity(const btVector3& gravity) = 0;
|
||||
virtual btVector3 getGravity () const = 0;
|
||||
|
||||
virtual void synchronizeMotionStates() = 0;
|
||||
|
||||
virtual void addRigidBody(btRigidBody* body) = 0;
|
||||
|
||||
virtual void removeRigidBody(btRigidBody* body) = 0;
|
||||
|
||||
virtual void setConstraintSolver(btConstraintSolver* solver) = 0;
|
||||
|
||||
virtual btConstraintSolver* getConstraintSolver() = 0;
|
||||
|
||||
virtual int getNumConstraints() const { return 0; }
|
||||
|
||||
virtual btTypedConstraint* getConstraint(int index) { (void)index; return 0; }
|
||||
|
||||
virtual const btTypedConstraint* getConstraint(int index) const { (void)index; return 0; }
|
||||
|
||||
virtual btDynamicsWorldType getWorldType() const=0;
|
||||
|
||||
virtual void clearForces() = 0;
|
||||
|
||||
/// Set the callback for when an internal tick (simulation substep) happens, optional user info
|
||||
void setInternalTickCallback(btInternalTickCallback cb, void* worldUserInfo=0,bool isPreTick=false)
|
||||
{
|
||||
if (isPreTick)
|
||||
{
|
||||
m_internalPreTickCallback = cb;
|
||||
} else
|
||||
{
|
||||
m_internalTickCallback = cb;
|
||||
}
|
||||
m_worldUserInfo = worldUserInfo;
|
||||
}
|
||||
|
||||
void setWorldUserInfo(void* worldUserInfo)
|
||||
{
|
||||
m_worldUserInfo = worldUserInfo;
|
||||
}
|
||||
|
||||
void* getWorldUserInfo() const
|
||||
{
|
||||
return m_worldUserInfo;
|
||||
}
|
||||
|
||||
btContactSolverInfo& getSolverInfo()
|
||||
{
|
||||
return m_solverInfo;
|
||||
}
|
||||
|
||||
|
||||
///obsolete, use addAction instead.
|
||||
virtual void addVehicle(btActionInterface* vehicle) {(void)vehicle;}
|
||||
///obsolete, use removeAction instead
|
||||
virtual void removeVehicle(btActionInterface* vehicle) {(void)vehicle;}
|
||||
///obsolete, use addAction instead.
|
||||
virtual void addCharacter(btActionInterface* character) {(void)character;}
|
||||
///obsolete, use removeAction instead
|
||||
virtual void removeCharacter(btActionInterface* character) {(void)character;}
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DYNAMICS_WORLD_H
|
||||
|
||||
|
403
libs/bullet/BulletDynamics/Dynamics/btRigidBody.cpp
Normal file
403
libs/bullet/BulletDynamics/Dynamics/btRigidBody.cpp
Normal file
@ -0,0 +1,403 @@
|
||||
/*
|
||||
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 "btRigidBody.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexShape.h"
|
||||
#include "LinearMath/btMinMax.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
#include "LinearMath/btMotionState.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btTypedConstraint.h"
|
||||
#include "LinearMath/btSerializer.h"
|
||||
|
||||
//'temporarily' global variables
|
||||
btScalar gDeactivationTime = btScalar(2.);
|
||||
bool gDisableDeactivation = false;
|
||||
static int uniqueId = 0;
|
||||
|
||||
|
||||
btRigidBody::btRigidBody(const btRigidBody::btRigidBodyConstructionInfo& constructionInfo)
|
||||
{
|
||||
setupRigidBody(constructionInfo);
|
||||
}
|
||||
|
||||
btRigidBody::btRigidBody(btScalar mass, btMotionState *motionState, btCollisionShape *collisionShape, const btVector3 &localInertia)
|
||||
{
|
||||
btRigidBodyConstructionInfo cinfo(mass,motionState,collisionShape,localInertia);
|
||||
setupRigidBody(cinfo);
|
||||
}
|
||||
|
||||
void btRigidBody::setupRigidBody(const btRigidBody::btRigidBodyConstructionInfo& constructionInfo)
|
||||
{
|
||||
|
||||
m_internalType=CO_RIGID_BODY;
|
||||
|
||||
m_linearVelocity.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
m_angularVelocity.setValue(btScalar(0.),btScalar(0.),btScalar(0.));
|
||||
m_angularFactor.setValue(1,1,1);
|
||||
m_linearFactor.setValue(1,1,1);
|
||||
m_gravity.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
m_gravity_acceleration.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
m_totalForce.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
m_totalTorque.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0)),
|
||||
m_linearDamping = btScalar(0.);
|
||||
m_angularDamping = btScalar(0.5);
|
||||
m_linearSleepingThreshold = constructionInfo.m_linearSleepingThreshold;
|
||||
m_angularSleepingThreshold = constructionInfo.m_angularSleepingThreshold;
|
||||
m_optionalMotionState = constructionInfo.m_motionState;
|
||||
m_contactSolverType = 0;
|
||||
m_frictionSolverType = 0;
|
||||
m_additionalDamping = constructionInfo.m_additionalDamping;
|
||||
m_additionalDampingFactor = constructionInfo.m_additionalDampingFactor;
|
||||
m_additionalLinearDampingThresholdSqr = constructionInfo.m_additionalLinearDampingThresholdSqr;
|
||||
m_additionalAngularDampingThresholdSqr = constructionInfo.m_additionalAngularDampingThresholdSqr;
|
||||
m_additionalAngularDampingFactor = constructionInfo.m_additionalAngularDampingFactor;
|
||||
|
||||
if (m_optionalMotionState)
|
||||
{
|
||||
m_optionalMotionState->getWorldTransform(m_worldTransform);
|
||||
} else
|
||||
{
|
||||
m_worldTransform = constructionInfo.m_startWorldTransform;
|
||||
}
|
||||
|
||||
m_interpolationWorldTransform = m_worldTransform;
|
||||
m_interpolationLinearVelocity.setValue(0,0,0);
|
||||
m_interpolationAngularVelocity.setValue(0,0,0);
|
||||
|
||||
//moved to btCollisionObject
|
||||
m_friction = constructionInfo.m_friction;
|
||||
m_restitution = constructionInfo.m_restitution;
|
||||
|
||||
setCollisionShape( constructionInfo.m_collisionShape );
|
||||
m_debugBodyId = uniqueId++;
|
||||
|
||||
setMassProps(constructionInfo.m_mass, constructionInfo.m_localInertia);
|
||||
setDamping(constructionInfo.m_linearDamping, constructionInfo.m_angularDamping);
|
||||
updateInertiaTensor();
|
||||
|
||||
m_rigidbodyFlags = 0;
|
||||
|
||||
|
||||
m_deltaLinearVelocity.setZero();
|
||||
m_deltaAngularVelocity.setZero();
|
||||
m_invMass = m_inverseMass*m_linearFactor;
|
||||
m_pushVelocity.setZero();
|
||||
m_turnVelocity.setZero();
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
void btRigidBody::predictIntegratedTransform(btScalar timeStep,btTransform& predictedTransform)
|
||||
{
|
||||
btTransformUtil::integrateTransform(m_worldTransform,m_linearVelocity,m_angularVelocity,timeStep,predictedTransform);
|
||||
}
|
||||
|
||||
void btRigidBody::saveKinematicState(btScalar timeStep)
|
||||
{
|
||||
//todo: clamp to some (user definable) safe minimum timestep, to limit maximum angular/linear velocities
|
||||
if (timeStep != btScalar(0.))
|
||||
{
|
||||
//if we use motionstate to synchronize world transforms, get the new kinematic/animated world transform
|
||||
if (getMotionState())
|
||||
getMotionState()->getWorldTransform(m_worldTransform);
|
||||
btVector3 linVel,angVel;
|
||||
|
||||
btTransformUtil::calculateVelocity(m_interpolationWorldTransform,m_worldTransform,timeStep,m_linearVelocity,m_angularVelocity);
|
||||
m_interpolationLinearVelocity = m_linearVelocity;
|
||||
m_interpolationAngularVelocity = m_angularVelocity;
|
||||
m_interpolationWorldTransform = m_worldTransform;
|
||||
//printf("angular = %f %f %f\n",m_angularVelocity.getX(),m_angularVelocity.getY(),m_angularVelocity.getZ());
|
||||
}
|
||||
}
|
||||
|
||||
void btRigidBody::getAabb(btVector3& aabbMin,btVector3& aabbMax) const
|
||||
{
|
||||
getCollisionShape()->getAabb(m_worldTransform,aabbMin,aabbMax);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
void btRigidBody::setGravity(const btVector3& acceleration)
|
||||
{
|
||||
if (m_inverseMass != btScalar(0.0))
|
||||
{
|
||||
m_gravity = acceleration * (btScalar(1.0) / m_inverseMass);
|
||||
}
|
||||
m_gravity_acceleration = acceleration;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void btRigidBody::setDamping(btScalar lin_damping, btScalar ang_damping)
|
||||
{
|
||||
m_linearDamping = btClamped(lin_damping, (btScalar)btScalar(0.0), (btScalar)btScalar(1.0));
|
||||
m_angularDamping = btClamped(ang_damping, (btScalar)btScalar(0.0), (btScalar)btScalar(1.0));
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
///applyDamping damps the velocity, using the given m_linearDamping and m_angularDamping
|
||||
void btRigidBody::applyDamping(btScalar timeStep)
|
||||
{
|
||||
//On new damping: see discussion/issue report here: http://code.google.com/p/bullet/issues/detail?id=74
|
||||
//todo: do some performance comparisons (but other parts of the engine are probably bottleneck anyway
|
||||
|
||||
//#define USE_OLD_DAMPING_METHOD 1
|
||||
#ifdef USE_OLD_DAMPING_METHOD
|
||||
m_linearVelocity *= GEN_clamped((btScalar(1.) - timeStep * m_linearDamping), (btScalar)btScalar(0.0), (btScalar)btScalar(1.0));
|
||||
m_angularVelocity *= GEN_clamped((btScalar(1.) - timeStep * m_angularDamping), (btScalar)btScalar(0.0), (btScalar)btScalar(1.0));
|
||||
#else
|
||||
m_linearVelocity *= btPow(btScalar(1)-m_linearDamping, timeStep);
|
||||
m_angularVelocity *= btPow(btScalar(1)-m_angularDamping, timeStep);
|
||||
#endif
|
||||
|
||||
if (m_additionalDamping)
|
||||
{
|
||||
//Additional damping can help avoiding lowpass jitter motion, help stability for ragdolls etc.
|
||||
//Such damping is undesirable, so once the overall simulation quality of the rigid body dynamics system has improved, this should become obsolete
|
||||
if ((m_angularVelocity.length2() < m_additionalAngularDampingThresholdSqr) &&
|
||||
(m_linearVelocity.length2() < m_additionalLinearDampingThresholdSqr))
|
||||
{
|
||||
m_angularVelocity *= m_additionalDampingFactor;
|
||||
m_linearVelocity *= m_additionalDampingFactor;
|
||||
}
|
||||
|
||||
|
||||
btScalar speed = m_linearVelocity.length();
|
||||
if (speed < m_linearDamping)
|
||||
{
|
||||
btScalar dampVel = btScalar(0.005);
|
||||
if (speed > dampVel)
|
||||
{
|
||||
btVector3 dir = m_linearVelocity.normalized();
|
||||
m_linearVelocity -= dir * dampVel;
|
||||
} else
|
||||
{
|
||||
m_linearVelocity.setValue(btScalar(0.),btScalar(0.),btScalar(0.));
|
||||
}
|
||||
}
|
||||
|
||||
btScalar angSpeed = m_angularVelocity.length();
|
||||
if (angSpeed < m_angularDamping)
|
||||
{
|
||||
btScalar angDampVel = btScalar(0.005);
|
||||
if (angSpeed > angDampVel)
|
||||
{
|
||||
btVector3 dir = m_angularVelocity.normalized();
|
||||
m_angularVelocity -= dir * angDampVel;
|
||||
} else
|
||||
{
|
||||
m_angularVelocity.setValue(btScalar(0.),btScalar(0.),btScalar(0.));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void btRigidBody::applyGravity()
|
||||
{
|
||||
if (isStaticOrKinematicObject())
|
||||
return;
|
||||
|
||||
applyCentralForce(m_gravity);
|
||||
|
||||
}
|
||||
|
||||
void btRigidBody::proceedToTransform(const btTransform& newTrans)
|
||||
{
|
||||
setCenterOfMassTransform( newTrans );
|
||||
}
|
||||
|
||||
|
||||
void btRigidBody::setMassProps(btScalar mass, const btVector3& inertia)
|
||||
{
|
||||
if (mass == btScalar(0.))
|
||||
{
|
||||
m_collisionFlags |= btCollisionObject::CF_STATIC_OBJECT;
|
||||
m_inverseMass = btScalar(0.);
|
||||
} else
|
||||
{
|
||||
m_collisionFlags &= (~btCollisionObject::CF_STATIC_OBJECT);
|
||||
m_inverseMass = btScalar(1.0) / mass;
|
||||
}
|
||||
|
||||
//Fg = m * a
|
||||
m_gravity = mass * m_gravity_acceleration;
|
||||
|
||||
m_invInertiaLocal.setValue(inertia.x() != btScalar(0.0) ? btScalar(1.0) / inertia.x(): btScalar(0.0),
|
||||
inertia.y() != btScalar(0.0) ? btScalar(1.0) / inertia.y(): btScalar(0.0),
|
||||
inertia.z() != btScalar(0.0) ? btScalar(1.0) / inertia.z(): btScalar(0.0));
|
||||
|
||||
m_invMass = m_linearFactor*m_inverseMass;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btRigidBody::updateInertiaTensor()
|
||||
{
|
||||
m_invInertiaTensorWorld = m_worldTransform.getBasis().scaled(m_invInertiaLocal) * m_worldTransform.getBasis().transpose();
|
||||
}
|
||||
|
||||
|
||||
void btRigidBody::integrateVelocities(btScalar step)
|
||||
{
|
||||
if (isStaticOrKinematicObject())
|
||||
return;
|
||||
|
||||
m_linearVelocity += m_totalForce * (m_inverseMass * step);
|
||||
m_angularVelocity += m_invInertiaTensorWorld * m_totalTorque * step;
|
||||
|
||||
#define MAX_ANGVEL SIMD_HALF_PI
|
||||
/// clamp angular velocity. collision calculations will fail on higher angular velocities
|
||||
btScalar angvel = m_angularVelocity.length();
|
||||
if (angvel*step > MAX_ANGVEL)
|
||||
{
|
||||
m_angularVelocity *= (MAX_ANGVEL/step) /angvel;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
btQuaternion btRigidBody::getOrientation() const
|
||||
{
|
||||
btQuaternion orn;
|
||||
m_worldTransform.getBasis().getRotation(orn);
|
||||
return orn;
|
||||
}
|
||||
|
||||
|
||||
void btRigidBody::setCenterOfMassTransform(const btTransform& xform)
|
||||
{
|
||||
|
||||
if (isStaticOrKinematicObject())
|
||||
{
|
||||
m_interpolationWorldTransform = m_worldTransform;
|
||||
} else
|
||||
{
|
||||
m_interpolationWorldTransform = xform;
|
||||
}
|
||||
m_interpolationLinearVelocity = getLinearVelocity();
|
||||
m_interpolationAngularVelocity = getAngularVelocity();
|
||||
m_worldTransform = xform;
|
||||
updateInertiaTensor();
|
||||
}
|
||||
|
||||
|
||||
bool btRigidBody::checkCollideWithOverride(btCollisionObject* co)
|
||||
{
|
||||
btRigidBody* otherRb = btRigidBody::upcast(co);
|
||||
if (!otherRb)
|
||||
return true;
|
||||
|
||||
for (int i = 0; i < m_constraintRefs.size(); ++i)
|
||||
{
|
||||
btTypedConstraint* c = m_constraintRefs[i];
|
||||
if (&c->getRigidBodyA() == otherRb || &c->getRigidBodyB() == otherRb)
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void btRigidBody::internalWritebackVelocity(btScalar timeStep)
|
||||
{
|
||||
(void) timeStep;
|
||||
if (m_inverseMass)
|
||||
{
|
||||
setLinearVelocity(getLinearVelocity()+ m_deltaLinearVelocity);
|
||||
setAngularVelocity(getAngularVelocity()+m_deltaAngularVelocity);
|
||||
|
||||
//correct the position/orientation based on push/turn recovery
|
||||
btTransform newTransform;
|
||||
btTransformUtil::integrateTransform(getWorldTransform(),m_pushVelocity,m_turnVelocity,timeStep,newTransform);
|
||||
setWorldTransform(newTransform);
|
||||
//m_originalBody->setCompanionId(-1);
|
||||
}
|
||||
// m_deltaLinearVelocity.setZero();
|
||||
// m_deltaAngularVelocity .setZero();
|
||||
// m_pushVelocity.setZero();
|
||||
// m_turnVelocity.setZero();
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btRigidBody::addConstraintRef(btTypedConstraint* c)
|
||||
{
|
||||
int index = m_constraintRefs.findLinearSearch(c);
|
||||
if (index == m_constraintRefs.size())
|
||||
m_constraintRefs.push_back(c);
|
||||
|
||||
m_checkCollideWith = true;
|
||||
}
|
||||
|
||||
void btRigidBody::removeConstraintRef(btTypedConstraint* c)
|
||||
{
|
||||
m_constraintRefs.remove(c);
|
||||
m_checkCollideWith = m_constraintRefs.size() > 0;
|
||||
}
|
||||
|
||||
int btRigidBody::calculateSerializeBufferSize() const
|
||||
{
|
||||
int sz = sizeof(btRigidBodyData);
|
||||
return sz;
|
||||
}
|
||||
|
||||
///fills the dataBuffer and returns the struct name (and 0 on failure)
|
||||
const char* btRigidBody::serialize(void* dataBuffer, class btSerializer* serializer) const
|
||||
{
|
||||
btRigidBodyData* rbd = (btRigidBodyData*) dataBuffer;
|
||||
|
||||
btCollisionObject::serialize(&rbd->m_collisionObjectData, serializer);
|
||||
|
||||
m_invInertiaTensorWorld.serialize(rbd->m_invInertiaTensorWorld);
|
||||
m_linearVelocity.serialize(rbd->m_linearVelocity);
|
||||
m_angularVelocity.serialize(rbd->m_angularVelocity);
|
||||
rbd->m_inverseMass = m_inverseMass;
|
||||
m_angularFactor.serialize(rbd->m_angularFactor);
|
||||
m_linearFactor.serialize(rbd->m_linearFactor);
|
||||
m_gravity.serialize(rbd->m_gravity);
|
||||
m_gravity_acceleration.serialize(rbd->m_gravity_acceleration);
|
||||
m_invInertiaLocal.serialize(rbd->m_invInertiaLocal);
|
||||
m_totalForce.serialize(rbd->m_totalForce);
|
||||
m_totalTorque.serialize(rbd->m_totalTorque);
|
||||
rbd->m_linearDamping = m_linearDamping;
|
||||
rbd->m_angularDamping = m_angularDamping;
|
||||
rbd->m_additionalDamping = m_additionalDamping;
|
||||
rbd->m_additionalDampingFactor = m_additionalDampingFactor;
|
||||
rbd->m_additionalLinearDampingThresholdSqr = m_additionalLinearDampingThresholdSqr;
|
||||
rbd->m_additionalAngularDampingThresholdSqr = m_additionalAngularDampingThresholdSqr;
|
||||
rbd->m_additionalAngularDampingFactor = m_additionalAngularDampingFactor;
|
||||
rbd->m_linearSleepingThreshold=m_linearSleepingThreshold;
|
||||
rbd->m_angularSleepingThreshold = m_angularSleepingThreshold;
|
||||
|
||||
return btRigidBodyDataName;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btRigidBody::serializeSingleObject(class btSerializer* serializer) const
|
||||
{
|
||||
btChunk* chunk = serializer->allocate(calculateSerializeBufferSize(),1);
|
||||
const char* structType = serialize(chunk->m_oldPtr, serializer);
|
||||
serializer->finalizeChunk(chunk,structType,BT_RIGIDBODY_CODE,(void*)this);
|
||||
}
|
||||
|
||||
|
690
libs/bullet/BulletDynamics/Dynamics/btRigidBody.h
Normal file
690
libs/bullet/BulletDynamics/Dynamics/btRigidBody.h
Normal file
@ -0,0 +1,690 @@
|
||||
/*
|
||||
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 RIGIDBODY_H
|
||||
#define RIGIDBODY_H
|
||||
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
|
||||
|
||||
class btCollisionShape;
|
||||
class btMotionState;
|
||||
class btTypedConstraint;
|
||||
|
||||
|
||||
extern btScalar gDeactivationTime;
|
||||
extern bool gDisableDeactivation;
|
||||
|
||||
#ifdef BT_USE_DOUBLE_PRECISION
|
||||
#define btRigidBodyData btRigidBodyDoubleData
|
||||
#define btRigidBodyDataName "btRigidBodyDoubleData"
|
||||
#else
|
||||
#define btRigidBodyData btRigidBodyFloatData
|
||||
#define btRigidBodyDataName "btRigidBodyFloatData"
|
||||
#endif //BT_USE_DOUBLE_PRECISION
|
||||
|
||||
|
||||
enum btRigidBodyFlags
|
||||
{
|
||||
BT_DISABLE_WORLD_GRAVITY = 1
|
||||
};
|
||||
|
||||
|
||||
///The btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape.
|
||||
///It is recommended for performance and memory use to share btCollisionShape objects whenever possible.
|
||||
///There are 3 types of rigid bodies:
|
||||
///- A) Dynamic rigid bodies, with positive mass. Motion is controlled by rigid body dynamics.
|
||||
///- B) Fixed objects with zero mass. They are not moving (basically collision objects)
|
||||
///- C) Kinematic objects, which are objects without mass, but the user can move them. There is on-way interaction, and Bullet calculates a velocity based on the timestep and previous and current world transform.
|
||||
///Bullet automatically deactivates dynamic rigid bodies, when the velocity is below a threshold for a given time.
|
||||
///Deactivated (sleeping) rigid bodies don't take any processing time, except a minor broadphase collision detection impact (to allow active objects to activate/wake up sleeping objects)
|
||||
class btRigidBody : public btCollisionObject
|
||||
{
|
||||
|
||||
btMatrix3x3 m_invInertiaTensorWorld;
|
||||
btVector3 m_linearVelocity;
|
||||
btVector3 m_angularVelocity;
|
||||
btScalar m_inverseMass;
|
||||
btVector3 m_linearFactor;
|
||||
|
||||
btVector3 m_gravity;
|
||||
btVector3 m_gravity_acceleration;
|
||||
btVector3 m_invInertiaLocal;
|
||||
btVector3 m_totalForce;
|
||||
btVector3 m_totalTorque;
|
||||
|
||||
btScalar m_linearDamping;
|
||||
btScalar m_angularDamping;
|
||||
|
||||
bool m_additionalDamping;
|
||||
btScalar m_additionalDampingFactor;
|
||||
btScalar m_additionalLinearDampingThresholdSqr;
|
||||
btScalar m_additionalAngularDampingThresholdSqr;
|
||||
btScalar m_additionalAngularDampingFactor;
|
||||
|
||||
|
||||
btScalar m_linearSleepingThreshold;
|
||||
btScalar m_angularSleepingThreshold;
|
||||
|
||||
//m_optionalMotionState allows to automatic synchronize the world transform for active objects
|
||||
btMotionState* m_optionalMotionState;
|
||||
|
||||
//keep track of typed constraints referencing this rigid body
|
||||
btAlignedObjectArray<btTypedConstraint*> m_constraintRefs;
|
||||
|
||||
int m_rigidbodyFlags;
|
||||
|
||||
int m_debugBodyId;
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
ATTRIBUTE_ALIGNED64(btVector3 m_deltaLinearVelocity);
|
||||
btVector3 m_deltaAngularVelocity;
|
||||
btVector3 m_angularFactor;
|
||||
btVector3 m_invMass;
|
||||
btVector3 m_pushVelocity;
|
||||
btVector3 m_turnVelocity;
|
||||
|
||||
|
||||
public:
|
||||
|
||||
|
||||
///The btRigidBodyConstructionInfo structure provides information to create a rigid body. Setting mass to zero creates a fixed (non-dynamic) rigid body.
|
||||
///For dynamic objects, you can use the collision shape to approximate the local inertia tensor, otherwise use the zero vector (default argument)
|
||||
///You can use the motion state to synchronize the world transform between physics and graphics objects.
|
||||
///And if the motion state is provided, the rigid body will initialize its initial world transform from the motion state,
|
||||
///m_startWorldTransform is only used when you don't provide a motion state.
|
||||
struct btRigidBodyConstructionInfo
|
||||
{
|
||||
btScalar m_mass;
|
||||
|
||||
///When a motionState is provided, the rigid body will initialize its world transform from the motion state
|
||||
///In this case, m_startWorldTransform is ignored.
|
||||
btMotionState* m_motionState;
|
||||
btTransform m_startWorldTransform;
|
||||
|
||||
btCollisionShape* m_collisionShape;
|
||||
btVector3 m_localInertia;
|
||||
btScalar m_linearDamping;
|
||||
btScalar m_angularDamping;
|
||||
|
||||
///best simulation results when friction is non-zero
|
||||
btScalar m_friction;
|
||||
///best simulation results using zero restitution.
|
||||
btScalar m_restitution;
|
||||
|
||||
btScalar m_linearSleepingThreshold;
|
||||
btScalar m_angularSleepingThreshold;
|
||||
|
||||
//Additional damping can help avoiding lowpass jitter motion, help stability for ragdolls etc.
|
||||
//Such damping is undesirable, so once the overall simulation quality of the rigid body dynamics system has improved, this should become obsolete
|
||||
bool m_additionalDamping;
|
||||
btScalar m_additionalDampingFactor;
|
||||
btScalar m_additionalLinearDampingThresholdSqr;
|
||||
btScalar m_additionalAngularDampingThresholdSqr;
|
||||
btScalar m_additionalAngularDampingFactor;
|
||||
|
||||
btRigidBodyConstructionInfo( btScalar mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia=btVector3(0,0,0)):
|
||||
m_mass(mass),
|
||||
m_motionState(motionState),
|
||||
m_collisionShape(collisionShape),
|
||||
m_localInertia(localInertia),
|
||||
m_linearDamping(btScalar(0.)),
|
||||
m_angularDamping(btScalar(0.)),
|
||||
m_friction(btScalar(0.5)),
|
||||
m_restitution(btScalar(0.)),
|
||||
m_linearSleepingThreshold(btScalar(0.8)),
|
||||
m_angularSleepingThreshold(btScalar(1.f)),
|
||||
m_additionalDamping(false),
|
||||
m_additionalDampingFactor(btScalar(0.005)),
|
||||
m_additionalLinearDampingThresholdSqr(btScalar(0.01)),
|
||||
m_additionalAngularDampingThresholdSqr(btScalar(0.01)),
|
||||
m_additionalAngularDampingFactor(btScalar(0.01))
|
||||
{
|
||||
m_startWorldTransform.setIdentity();
|
||||
}
|
||||
};
|
||||
|
||||
///btRigidBody constructor using construction info
|
||||
btRigidBody( const btRigidBodyConstructionInfo& constructionInfo);
|
||||
|
||||
///btRigidBody constructor for backwards compatibility.
|
||||
///To specify friction (etc) during rigid body construction, please use the other constructor (using btRigidBodyConstructionInfo)
|
||||
btRigidBody( btScalar mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia=btVector3(0,0,0));
|
||||
|
||||
|
||||
virtual ~btRigidBody()
|
||||
{
|
||||
//No constraints should point to this rigidbody
|
||||
//Remove constraints from the dynamics world before you delete the related rigidbodies.
|
||||
btAssert(m_constraintRefs.size()==0);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
///setupRigidBody is only used internally by the constructor
|
||||
void setupRigidBody(const btRigidBodyConstructionInfo& constructionInfo);
|
||||
|
||||
public:
|
||||
|
||||
void proceedToTransform(const btTransform& newTrans);
|
||||
|
||||
///to keep collision detection and dynamics separate we don't store a rigidbody pointer
|
||||
///but a rigidbody is derived from btCollisionObject, so we can safely perform an upcast
|
||||
static const btRigidBody* upcast(const btCollisionObject* colObj)
|
||||
{
|
||||
if (colObj->getInternalType()&btCollisionObject::CO_RIGID_BODY)
|
||||
return (const btRigidBody*)colObj;
|
||||
return 0;
|
||||
}
|
||||
static btRigidBody* upcast(btCollisionObject* colObj)
|
||||
{
|
||||
if (colObj->getInternalType()&btCollisionObject::CO_RIGID_BODY)
|
||||
return (btRigidBody*)colObj;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/// continuous collision detection needs prediction
|
||||
void predictIntegratedTransform(btScalar step, btTransform& predictedTransform) ;
|
||||
|
||||
void saveKinematicState(btScalar step);
|
||||
|
||||
void applyGravity();
|
||||
|
||||
void setGravity(const btVector3& acceleration);
|
||||
|
||||
const btVector3& getGravity() const
|
||||
{
|
||||
return m_gravity_acceleration;
|
||||
}
|
||||
|
||||
void setDamping(btScalar lin_damping, btScalar ang_damping);
|
||||
|
||||
btScalar getLinearDamping() const
|
||||
{
|
||||
return m_linearDamping;
|
||||
}
|
||||
|
||||
btScalar getAngularDamping() const
|
||||
{
|
||||
return m_angularDamping;
|
||||
}
|
||||
|
||||
btScalar getLinearSleepingThreshold() const
|
||||
{
|
||||
return m_linearSleepingThreshold;
|
||||
}
|
||||
|
||||
btScalar getAngularSleepingThreshold() const
|
||||
{
|
||||
return m_angularSleepingThreshold;
|
||||
}
|
||||
|
||||
void applyDamping(btScalar timeStep);
|
||||
|
||||
SIMD_FORCE_INLINE const btCollisionShape* getCollisionShape() const {
|
||||
return m_collisionShape;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE btCollisionShape* getCollisionShape() {
|
||||
return m_collisionShape;
|
||||
}
|
||||
|
||||
void setMassProps(btScalar mass, const btVector3& inertia);
|
||||
|
||||
const btVector3& getLinearFactor() const
|
||||
{
|
||||
return m_linearFactor;
|
||||
}
|
||||
void setLinearFactor(const btVector3& linearFactor)
|
||||
{
|
||||
m_linearFactor = linearFactor;
|
||||
m_invMass = m_linearFactor*m_inverseMass;
|
||||
}
|
||||
btScalar getInvMass() const { return m_inverseMass; }
|
||||
const btMatrix3x3& getInvInertiaTensorWorld() const {
|
||||
return m_invInertiaTensorWorld;
|
||||
}
|
||||
|
||||
void integrateVelocities(btScalar step);
|
||||
|
||||
void setCenterOfMassTransform(const btTransform& xform);
|
||||
|
||||
void applyCentralForce(const btVector3& force)
|
||||
{
|
||||
m_totalForce += force*m_linearFactor;
|
||||
}
|
||||
|
||||
const btVector3& getTotalForce()
|
||||
{
|
||||
return m_totalForce;
|
||||
};
|
||||
|
||||
const btVector3& getTotalTorque()
|
||||
{
|
||||
return m_totalTorque;
|
||||
};
|
||||
|
||||
const btVector3& getInvInertiaDiagLocal() const
|
||||
{
|
||||
return m_invInertiaLocal;
|
||||
};
|
||||
|
||||
void setInvInertiaDiagLocal(const btVector3& diagInvInertia)
|
||||
{
|
||||
m_invInertiaLocal = diagInvInertia;
|
||||
}
|
||||
|
||||
void setSleepingThresholds(btScalar linear,btScalar angular)
|
||||
{
|
||||
m_linearSleepingThreshold = linear;
|
||||
m_angularSleepingThreshold = angular;
|
||||
}
|
||||
|
||||
void applyTorque(const btVector3& torque)
|
||||
{
|
||||
m_totalTorque += torque*m_angularFactor;
|
||||
}
|
||||
|
||||
void applyForce(const btVector3& force, const btVector3& rel_pos)
|
||||
{
|
||||
applyCentralForce(force);
|
||||
applyTorque(rel_pos.cross(force*m_linearFactor));
|
||||
}
|
||||
|
||||
void applyCentralImpulse(const btVector3& impulse)
|
||||
{
|
||||
m_linearVelocity += impulse *m_linearFactor * m_inverseMass;
|
||||
}
|
||||
|
||||
void applyTorqueImpulse(const btVector3& torque)
|
||||
{
|
||||
m_angularVelocity += m_invInertiaTensorWorld * torque * m_angularFactor;
|
||||
}
|
||||
|
||||
void applyImpulse(const btVector3& impulse, const btVector3& rel_pos)
|
||||
{
|
||||
if (m_inverseMass != btScalar(0.))
|
||||
{
|
||||
applyCentralImpulse(impulse);
|
||||
if (m_angularFactor)
|
||||
{
|
||||
applyTorqueImpulse(rel_pos.cross(impulse*m_linearFactor));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void clearForces()
|
||||
{
|
||||
m_totalForce.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
m_totalTorque.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
}
|
||||
|
||||
void updateInertiaTensor();
|
||||
|
||||
const btVector3& getCenterOfMassPosition() const {
|
||||
return m_worldTransform.getOrigin();
|
||||
}
|
||||
btQuaternion getOrientation() const;
|
||||
|
||||
const btTransform& getCenterOfMassTransform() const {
|
||||
return m_worldTransform;
|
||||
}
|
||||
const btVector3& getLinearVelocity() const {
|
||||
return m_linearVelocity;
|
||||
}
|
||||
const btVector3& getAngularVelocity() const {
|
||||
return m_angularVelocity;
|
||||
}
|
||||
|
||||
|
||||
inline void setLinearVelocity(const btVector3& lin_vel)
|
||||
{
|
||||
m_linearVelocity = lin_vel;
|
||||
}
|
||||
|
||||
inline void setAngularVelocity(const btVector3& ang_vel)
|
||||
{
|
||||
m_angularVelocity = ang_vel;
|
||||
}
|
||||
|
||||
btVector3 getVelocityInLocalPoint(const btVector3& rel_pos) const
|
||||
{
|
||||
//we also calculate lin/ang velocity for kinematic objects
|
||||
return m_linearVelocity + m_angularVelocity.cross(rel_pos);
|
||||
|
||||
//for kinematic objects, we could also use use:
|
||||
// return (m_worldTransform(rel_pos) - m_interpolationWorldTransform(rel_pos)) / m_kinematicTimeStep;
|
||||
}
|
||||
|
||||
void translate(const btVector3& v)
|
||||
{
|
||||
m_worldTransform.getOrigin() += v;
|
||||
}
|
||||
|
||||
|
||||
void getAabb(btVector3& aabbMin,btVector3& aabbMax) const;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
SIMD_FORCE_INLINE btScalar computeImpulseDenominator(const btVector3& pos, const btVector3& normal) const
|
||||
{
|
||||
btVector3 r0 = pos - getCenterOfMassPosition();
|
||||
|
||||
btVector3 c0 = (r0).cross(normal);
|
||||
|
||||
btVector3 vec = (c0 * getInvInertiaTensorWorld()).cross(r0);
|
||||
|
||||
return m_inverseMass + normal.dot(vec);
|
||||
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE btScalar computeAngularImpulseDenominator(const btVector3& axis) const
|
||||
{
|
||||
btVector3 vec = axis * getInvInertiaTensorWorld();
|
||||
return axis.dot(vec);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void updateDeactivation(btScalar timeStep)
|
||||
{
|
||||
if ( (getActivationState() == ISLAND_SLEEPING) || (getActivationState() == DISABLE_DEACTIVATION))
|
||||
return;
|
||||
|
||||
if ((getLinearVelocity().length2() < m_linearSleepingThreshold*m_linearSleepingThreshold) &&
|
||||
(getAngularVelocity().length2() < m_angularSleepingThreshold*m_angularSleepingThreshold))
|
||||
{
|
||||
m_deactivationTime += timeStep;
|
||||
} else
|
||||
{
|
||||
m_deactivationTime=btScalar(0.);
|
||||
setActivationState(0);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool wantsSleeping()
|
||||
{
|
||||
|
||||
if (getActivationState() == DISABLE_DEACTIVATION)
|
||||
return false;
|
||||
|
||||
//disable deactivation
|
||||
if (gDisableDeactivation || (gDeactivationTime == btScalar(0.)))
|
||||
return false;
|
||||
|
||||
if ( (getActivationState() == ISLAND_SLEEPING) || (getActivationState() == WANTS_DEACTIVATION))
|
||||
return true;
|
||||
|
||||
if (m_deactivationTime> gDeactivationTime)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
|
||||
const btBroadphaseProxy* getBroadphaseProxy() const
|
||||
{
|
||||
return m_broadphaseHandle;
|
||||
}
|
||||
btBroadphaseProxy* getBroadphaseProxy()
|
||||
{
|
||||
return m_broadphaseHandle;
|
||||
}
|
||||
void setNewBroadphaseProxy(btBroadphaseProxy* broadphaseProxy)
|
||||
{
|
||||
m_broadphaseHandle = broadphaseProxy;
|
||||
}
|
||||
|
||||
//btMotionState allows to automatic synchronize the world transform for active objects
|
||||
btMotionState* getMotionState()
|
||||
{
|
||||
return m_optionalMotionState;
|
||||
}
|
||||
const btMotionState* getMotionState() const
|
||||
{
|
||||
return m_optionalMotionState;
|
||||
}
|
||||
void setMotionState(btMotionState* motionState)
|
||||
{
|
||||
m_optionalMotionState = motionState;
|
||||
if (m_optionalMotionState)
|
||||
motionState->getWorldTransform(m_worldTransform);
|
||||
}
|
||||
|
||||
//for experimental overriding of friction/contact solver func
|
||||
int m_contactSolverType;
|
||||
int m_frictionSolverType;
|
||||
|
||||
void setAngularFactor(const btVector3& angFac)
|
||||
{
|
||||
m_angularFactor = angFac;
|
||||
}
|
||||
|
||||
void setAngularFactor(btScalar angFac)
|
||||
{
|
||||
m_angularFactor.setValue(angFac,angFac,angFac);
|
||||
}
|
||||
const btVector3& getAngularFactor() const
|
||||
{
|
||||
return m_angularFactor;
|
||||
}
|
||||
|
||||
//is this rigidbody added to a btCollisionWorld/btDynamicsWorld/btBroadphase?
|
||||
bool isInWorld() const
|
||||
{
|
||||
return (getBroadphaseProxy() != 0);
|
||||
}
|
||||
|
||||
virtual bool checkCollideWithOverride(btCollisionObject* co);
|
||||
|
||||
void addConstraintRef(btTypedConstraint* c);
|
||||
void removeConstraintRef(btTypedConstraint* c);
|
||||
|
||||
btTypedConstraint* getConstraintRef(int index)
|
||||
{
|
||||
return m_constraintRefs[index];
|
||||
}
|
||||
|
||||
int getNumConstraintRefs()
|
||||
{
|
||||
return m_constraintRefs.size();
|
||||
}
|
||||
|
||||
void setFlags(int flags)
|
||||
{
|
||||
m_rigidbodyFlags = flags;
|
||||
}
|
||||
|
||||
int getFlags() const
|
||||
{
|
||||
return m_rigidbodyFlags;
|
||||
}
|
||||
|
||||
const btVector3& getDeltaLinearVelocity() const
|
||||
{
|
||||
return m_deltaLinearVelocity;
|
||||
}
|
||||
|
||||
const btVector3& getDeltaAngularVelocity() const
|
||||
{
|
||||
return m_deltaAngularVelocity;
|
||||
}
|
||||
|
||||
const btVector3& getPushVelocity() const
|
||||
{
|
||||
return m_pushVelocity;
|
||||
}
|
||||
|
||||
const btVector3& getTurnVelocity() const
|
||||
{
|
||||
return m_turnVelocity;
|
||||
}
|
||||
|
||||
|
||||
////////////////////////////////////////////////
|
||||
///some internal methods, don't use them
|
||||
|
||||
btVector3& internalGetDeltaLinearVelocity()
|
||||
{
|
||||
return m_deltaLinearVelocity;
|
||||
}
|
||||
|
||||
btVector3& internalGetDeltaAngularVelocity()
|
||||
{
|
||||
return m_deltaAngularVelocity;
|
||||
}
|
||||
|
||||
const btVector3& internalGetAngularFactor() const
|
||||
{
|
||||
return m_angularFactor;
|
||||
}
|
||||
|
||||
const btVector3& internalGetInvMass() const
|
||||
{
|
||||
return m_invMass;
|
||||
}
|
||||
|
||||
btVector3& internalGetPushVelocity()
|
||||
{
|
||||
return m_pushVelocity;
|
||||
}
|
||||
|
||||
btVector3& internalGetTurnVelocity()
|
||||
{
|
||||
return m_turnVelocity;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void internalGetVelocityInLocalPointObsolete(const btVector3& rel_pos, btVector3& velocity ) const
|
||||
{
|
||||
velocity = getLinearVelocity()+m_deltaLinearVelocity + (getAngularVelocity()+m_deltaAngularVelocity).cross(rel_pos);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void internalGetAngularVelocity(btVector3& angVel) const
|
||||
{
|
||||
angVel = getAngularVelocity()+m_deltaAngularVelocity;
|
||||
}
|
||||
|
||||
|
||||
//Optimization for the iterative solver: avoid calculating constant terms involving inertia, normal, relative position
|
||||
SIMD_FORCE_INLINE void internalApplyImpulse(const btVector3& linearComponent, const btVector3& angularComponent,const btScalar impulseMagnitude)
|
||||
{
|
||||
if (m_inverseMass)
|
||||
{
|
||||
m_deltaLinearVelocity += linearComponent*impulseMagnitude;
|
||||
m_deltaAngularVelocity += angularComponent*(impulseMagnitude*m_angularFactor);
|
||||
}
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void internalApplyPushImpulse(const btVector3& linearComponent, const btVector3& angularComponent,btScalar impulseMagnitude)
|
||||
{
|
||||
if (m_inverseMass)
|
||||
{
|
||||
m_pushVelocity += linearComponent*impulseMagnitude;
|
||||
m_turnVelocity += angularComponent*(impulseMagnitude*m_angularFactor);
|
||||
}
|
||||
}
|
||||
|
||||
void internalWritebackVelocity()
|
||||
{
|
||||
if (m_inverseMass)
|
||||
{
|
||||
setLinearVelocity(getLinearVelocity()+ m_deltaLinearVelocity);
|
||||
setAngularVelocity(getAngularVelocity()+m_deltaAngularVelocity);
|
||||
//m_deltaLinearVelocity.setZero();
|
||||
//m_deltaAngularVelocity .setZero();
|
||||
//m_originalBody->setCompanionId(-1);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void internalWritebackVelocity(btScalar timeStep);
|
||||
|
||||
|
||||
///////////////////////////////////////////////
|
||||
|
||||
virtual int calculateSerializeBufferSize() const;
|
||||
|
||||
///fills the dataBuffer and returns the struct name (and 0 on failure)
|
||||
virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
|
||||
|
||||
virtual void serializeSingleObject(class btSerializer* serializer) const;
|
||||
|
||||
};
|
||||
|
||||
//@todo add m_optionalMotionState and m_constraintRefs to btRigidBodyData
|
||||
///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
|
||||
struct btRigidBodyFloatData
|
||||
{
|
||||
btCollisionObjectFloatData m_collisionObjectData;
|
||||
btMatrix3x3FloatData m_invInertiaTensorWorld;
|
||||
btVector3FloatData m_linearVelocity;
|
||||
btVector3FloatData m_angularVelocity;
|
||||
btVector3FloatData m_angularFactor;
|
||||
btVector3FloatData m_linearFactor;
|
||||
btVector3FloatData m_gravity;
|
||||
btVector3FloatData m_gravity_acceleration;
|
||||
btVector3FloatData m_invInertiaLocal;
|
||||
btVector3FloatData m_totalForce;
|
||||
btVector3FloatData m_totalTorque;
|
||||
float m_inverseMass;
|
||||
float m_linearDamping;
|
||||
float m_angularDamping;
|
||||
float m_additionalDampingFactor;
|
||||
float m_additionalLinearDampingThresholdSqr;
|
||||
float m_additionalAngularDampingThresholdSqr;
|
||||
float m_additionalAngularDampingFactor;
|
||||
float m_linearSleepingThreshold;
|
||||
float m_angularSleepingThreshold;
|
||||
int m_additionalDamping;
|
||||
};
|
||||
|
||||
///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
|
||||
struct btRigidBodyDoubleData
|
||||
{
|
||||
btCollisionObjectDoubleData m_collisionObjectData;
|
||||
btMatrix3x3DoubleData m_invInertiaTensorWorld;
|
||||
btVector3DoubleData m_linearVelocity;
|
||||
btVector3DoubleData m_angularVelocity;
|
||||
btVector3DoubleData m_angularFactor;
|
||||
btVector3DoubleData m_linearFactor;
|
||||
btVector3DoubleData m_gravity;
|
||||
btVector3DoubleData m_gravity_acceleration;
|
||||
btVector3DoubleData m_invInertiaLocal;
|
||||
btVector3DoubleData m_totalForce;
|
||||
btVector3DoubleData m_totalTorque;
|
||||
double m_inverseMass;
|
||||
double m_linearDamping;
|
||||
double m_angularDamping;
|
||||
double m_additionalDampingFactor;
|
||||
double m_additionalLinearDampingThresholdSqr;
|
||||
double m_additionalAngularDampingThresholdSqr;
|
||||
double m_additionalAngularDampingFactor;
|
||||
double m_linearSleepingThreshold;
|
||||
double m_angularSleepingThreshold;
|
||||
int m_additionalDamping;
|
||||
char m_padding[4];
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif
|
||||
|
253
libs/bullet/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp
Normal file
253
libs/bullet/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp
Normal file
@ -0,0 +1,253 @@
|
||||
/*
|
||||
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 "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"
|
||||
|
||||
|
||||
/*
|
||||
Make sure this dummy function never changes so that it
|
||||
can be used by probes that are checking whether the
|
||||
library is actually installed.
|
||||
*/
|
||||
extern "C"
|
||||
{
|
||||
void btBulletDynamicsProbe ();
|
||||
void btBulletDynamicsProbe () {}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
btSimpleDynamicsWorld::btSimpleDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration)
|
||||
:btDynamicsWorld(dispatcher,pairCache,collisionConfiguration),
|
||||
m_constraintSolver(constraintSolver),
|
||||
m_ownsConstraintSolver(false),
|
||||
m_gravity(0,0,-10)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
|
||||
btSimpleDynamicsWorld::~btSimpleDynamicsWorld()
|
||||
{
|
||||
if (m_ownsConstraintSolver)
|
||||
btAlignedFree( m_constraintSolver);
|
||||
}
|
||||
|
||||
int btSimpleDynamicsWorld::stepSimulation( btScalar timeStep,int maxSubSteps, btScalar fixedTimeStep)
|
||||
{
|
||||
(void)fixedTimeStep;
|
||||
(void)maxSubSteps;
|
||||
|
||||
|
||||
///apply gravity, predict motion
|
||||
predictUnconstraintMotion(timeStep);
|
||||
|
||||
btDispatcherInfo& dispatchInfo = getDispatchInfo();
|
||||
dispatchInfo.m_timeStep = timeStep;
|
||||
dispatchInfo.m_stepCount = 0;
|
||||
dispatchInfo.m_debugDraw = getDebugDrawer();
|
||||
|
||||
///perform collision detection
|
||||
performDiscreteCollisionDetection();
|
||||
|
||||
///solve contact constraints
|
||||
int numManifolds = m_dispatcher1->getNumManifolds();
|
||||
if (numManifolds)
|
||||
{
|
||||
btPersistentManifold** manifoldPtr = ((btCollisionDispatcher*)m_dispatcher1)->getInternalManifoldPointer();
|
||||
|
||||
btContactSolverInfo infoGlobal;
|
||||
infoGlobal.m_timeStep = timeStep;
|
||||
m_constraintSolver->prepareSolve(0,numManifolds);
|
||||
m_constraintSolver->solveGroup(0,0,manifoldPtr, numManifolds,0,0,infoGlobal,m_debugDrawer, m_stackAlloc,m_dispatcher1);
|
||||
m_constraintSolver->allSolved(infoGlobal,m_debugDrawer, m_stackAlloc);
|
||||
}
|
||||
|
||||
///integrate transforms
|
||||
integrateTransforms(timeStep);
|
||||
|
||||
updateAabbs();
|
||||
|
||||
synchronizeMotionStates();
|
||||
|
||||
clearForces();
|
||||
|
||||
return 1;
|
||||
|
||||
}
|
||||
|
||||
void btSimpleDynamicsWorld::clearForces()
|
||||
{
|
||||
///@todo: iterate over awake simulation islands!
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
body->clearForces();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::setGravity(const btVector3& gravity)
|
||||
{
|
||||
m_gravity = gravity;
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
body->setGravity(gravity);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
btVector3 btSimpleDynamicsWorld::getGravity () const
|
||||
{
|
||||
return m_gravity;
|
||||
}
|
||||
|
||||
void btSimpleDynamicsWorld::removeRigidBody(btRigidBody* body)
|
||||
{
|
||||
btCollisionWorld::removeCollisionObject(body);
|
||||
}
|
||||
|
||||
void btSimpleDynamicsWorld::removeCollisionObject(btCollisionObject* collisionObject)
|
||||
{
|
||||
btRigidBody* body = btRigidBody::upcast(collisionObject);
|
||||
if (body)
|
||||
removeRigidBody(body);
|
||||
else
|
||||
btCollisionWorld::removeCollisionObject(collisionObject);
|
||||
}
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::addRigidBody(btRigidBody* body)
|
||||
{
|
||||
body->setGravity(m_gravity);
|
||||
|
||||
if (body->getCollisionShape())
|
||||
{
|
||||
addCollisionObject(body);
|
||||
}
|
||||
}
|
||||
|
||||
void btSimpleDynamicsWorld::updateAabbs()
|
||||
{
|
||||
btTransform predictedTrans;
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
if (body->isActive() && (!body->isStaticObject()))
|
||||
{
|
||||
btVector3 minAabb,maxAabb;
|
||||
colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
|
||||
btBroadphaseInterface* bp = getBroadphase();
|
||||
bp->setAabb(body->getBroadphaseHandle(),minAabb,maxAabb, m_dispatcher1);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void btSimpleDynamicsWorld::integrateTransforms(btScalar timeStep)
|
||||
{
|
||||
btTransform predictedTrans;
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
if (body->isActive() && (!body->isStaticObject()))
|
||||
{
|
||||
body->predictIntegratedTransform(timeStep, predictedTrans);
|
||||
body->proceedToTransform( predictedTrans);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
|
||||
{
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
if (!body->isStaticObject())
|
||||
{
|
||||
if (body->isActive())
|
||||
{
|
||||
body->applyGravity();
|
||||
body->integrateVelocities( timeStep);
|
||||
body->applyDamping(timeStep);
|
||||
body->predictIntegratedTransform(timeStep,body->getInterpolationWorldTransform());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::synchronizeMotionStates()
|
||||
{
|
||||
///@todo: iterate over awake simulation islands!
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body && body->getMotionState())
|
||||
{
|
||||
if (body->getActivationState() != ISLAND_SLEEPING)
|
||||
{
|
||||
body->getMotionState()->setWorldTransform(body->getWorldTransform());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
void btSimpleDynamicsWorld::setConstraintSolver(btConstraintSolver* solver)
|
||||
{
|
||||
if (m_ownsConstraintSolver)
|
||||
{
|
||||
btAlignedFree(m_constraintSolver);
|
||||
}
|
||||
m_ownsConstraintSolver = false;
|
||||
m_constraintSolver = solver;
|
||||
}
|
||||
|
||||
btConstraintSolver* btSimpleDynamicsWorld::getConstraintSolver()
|
||||
{
|
||||
return m_constraintSolver;
|
||||
}
|
81
libs/bullet/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h
Normal file
81
libs/bullet/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h
Normal file
@ -0,0 +1,81 @@
|
||||
/*
|
||||
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;
|
||||
|
||||
///The btSimpleDynamicsWorld serves as unit-test and to verify more complicated and optimized dynamics worlds.
|
||||
///Please use btDiscreteDynamicsWorld instead (or btContinuousDynamicsWorld once it is finished).
|
||||
class btSimpleDynamicsWorld : public btDynamicsWorld
|
||||
{
|
||||
protected:
|
||||
|
||||
btConstraintSolver* m_constraintSolver;
|
||||
|
||||
bool m_ownsConstraintSolver;
|
||||
|
||||
void predictUnconstraintMotion(btScalar timeStep);
|
||||
|
||||
void integrateTransforms(btScalar timeStep);
|
||||
|
||||
btVector3 m_gravity;
|
||||
|
||||
public:
|
||||
|
||||
|
||||
|
||||
///this btSimpleDynamicsWorld constructor creates dispatcher, broadphase pairCache and constraintSolver
|
||||
btSimpleDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration);
|
||||
|
||||
virtual ~btSimpleDynamicsWorld();
|
||||
|
||||
///maxSubSteps/fixedTimeStep for interpolation is currently ignored for btSimpleDynamicsWorld, use btDiscreteDynamicsWorld instead
|
||||
virtual int stepSimulation( btScalar timeStep,int maxSubSteps=1, btScalar fixedTimeStep=btScalar(1.)/btScalar(60.));
|
||||
|
||||
virtual void setGravity(const btVector3& gravity);
|
||||
|
||||
virtual btVector3 getGravity () const;
|
||||
|
||||
virtual void addRigidBody(btRigidBody* body);
|
||||
|
||||
virtual void removeRigidBody(btRigidBody* body);
|
||||
|
||||
///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject
|
||||
virtual void removeCollisionObject(btCollisionObject* collisionObject);
|
||||
|
||||
virtual void updateAabbs();
|
||||
|
||||
virtual void synchronizeMotionStates();
|
||||
|
||||
virtual void setConstraintSolver(btConstraintSolver* solver);
|
||||
|
||||
virtual btConstraintSolver* getConstraintSolver();
|
||||
|
||||
virtual btDynamicsWorldType getWorldType() const
|
||||
{
|
||||
return BT_SIMPLE_DYNAMICS_WORLD;
|
||||
}
|
||||
|
||||
virtual void clearForces();
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_SIMPLE_DYNAMICS_WORLD_H
|
Reference in New Issue
Block a user