added physics-debugging

didn't check every single file, so might have broken some gameengine stuff, will fix it this weekend!
This commit is contained in:
Erwin Coumans
2005-07-29 18:14:41 +00:00
parent 7d797797c8
commit dad6ef9045
32 changed files with 341 additions and 166 deletions

View File

@@ -11,6 +11,14 @@
#include "BoxShape.h" #include "BoxShape.h"
SimdVector3 BoxShape::GetHalfExtents() const
{
SimdVector3 scalingCorrectedHalfExtents = m_boxHalfExtents1 * m_localScaling;
SimdVector3 marginCorrection (CONVEX_DISTANCE_MARGIN,CONVEX_DISTANCE_MARGIN,CONVEX_DISTANCE_MARGIN);
return (scalingCorrectedHalfExtents - marginCorrection).absolute();
}
void BoxShape::GetAabb(const SimdTransform& t,SimdVector3& aabbMin,SimdVector3& aabbMax) const void BoxShape::GetAabb(const SimdTransform& t,SimdVector3& aabbMin,SimdVector3& aabbMax) const
{ {
@@ -25,8 +33,9 @@ void BoxShape::GetAabb(const SimdTransform& t,SimdVector3& aabbMin,SimdVector3&
//todo: this is a quick fix, we need to enlarge the aabb dependent on several criteria //todo: this is a quick fix, we need to enlarge the aabb dependent on several criteria
//extent += SimdVector3(.2f,.2f,.2f); // SimdVector3 extra(1,1,1);
// extent += extra;
aabbMin = center - extent; aabbMin = center - extent;
aabbMax = center + extent; aabbMax = center + extent;

View File

@@ -32,10 +32,7 @@ public:
} }
SimdVector3 GetHalfExtents() const{ return m_boxHalfExtents1 * m_localScaling;} SimdVector3 GetHalfExtents() const;
//const SimdVector3& GetHalfExtents() const{ return m_boxHalfExtents1;}
virtual int GetShapeType() const { return BOX_SHAPE_PROXYTYPE;} virtual int GetShapeType() const { return BOX_SHAPE_PROXYTYPE;}

View File

@@ -118,13 +118,13 @@ void ConvexHullShape::GetEdge(int i,SimdPoint3& pa,SimdPoint3& pb) const
int index0 = i%m_points.size(); int index0 = i%m_points.size();
int index1 = i/m_points.size(); int index1 = i/m_points.size();
pa = m_points[index0]; pa = m_points[index0]*m_localScaling;
pb = m_points[index1]; pb = m_points[index1]*m_localScaling;
} }
void ConvexHullShape::GetVertex(int i,SimdPoint3& vtx) const void ConvexHullShape::GetVertex(int i,SimdPoint3& vtx) const
{ {
vtx = m_points[i]; vtx = m_points[i]*m_localScaling;
} }
int ConvexHullShape::GetNumPlanes() const int ConvexHullShape::GetNumPlanes() const

View File

@@ -3,7 +3,7 @@
//used by Gjk and some other algorithms //used by Gjk and some other algorithms
#define CONVEX_DISTANCE_MARGIN 0.05f// 0.1f//;//0.01f #define CONVEX_DISTANCE_MARGIN 0.04f// 0.1f//;//0.01f

View File

@@ -16,6 +16,7 @@
#include <SimdVector3.h> #include <SimdVector3.h>
#include <SimdScalar.h> #include <SimdScalar.h>
class MinkowskiSumShape; class MinkowskiSumShape;
#include "IDebugDraw.h"
/// ConvexCast is an interface for Casting /// ConvexCast is an interface for Casting
class ConvexCast class ConvexCast
@@ -30,18 +31,23 @@ public:
struct CastResult struct CastResult
{ {
//virtual bool addRayResult(const SimdVector3& normal,SimdScalar fraction) = 0; //virtual bool addRayResult(const SimdVector3& normal,SimdScalar fraction) = 0;
virtual void DebugDraw(SimdScalar fraction) {} virtual void DebugDraw(SimdScalar fraction) {}
virtual void DrawCoordSystem(const SimdTransform& trans) {} virtual void DrawCoordSystem(const SimdTransform& trans) {}
CastResult() CastResult()
:m_fraction(1e30f) :m_fraction(1e30f),
m_debugDrawer(0)
{ {
} }
SimdVector3 m_normal; SimdVector3 m_normal;
SimdScalar m_fraction; SimdScalar m_fraction;
SimdTransform m_hitTransformA; SimdTransform m_hitTransformA;
SimdTransform m_hitTransformB; SimdTransform m_hitTransformB;
IDebugDraw* m_debugDrawer;
}; };

View File

@@ -111,6 +111,10 @@ void PersistentManifold::AddManifoldPoint(const ManifoldPoint& newPoint)
ReplaceContactPoint(newPoint,insertIndex); ReplaceContactPoint(newPoint,insertIndex);
} }
float PersistentManifold::GetManifoldMargin() const
{
return 0.02f;
}
void PersistentManifold::RefreshContactPoints(const SimdTransform& trA,const SimdTransform& trB) void PersistentManifold::RefreshContactPoints(const SimdTransform& trA,const SimdTransform& trB)
{ {

View File

@@ -37,6 +37,8 @@ class PersistentManifold
/// sort cached points so most isolated points come first /// sort cached points so most isolated points come first
int SortCachedPoints(const ManifoldPoint& pt); int SortCachedPoints(const ManifoldPoint& pt);
int FindContactPoint(const ManifoldPoint* unUsed, int numUnused,const ManifoldPoint& pt);
public: public:
int m_index1; int m_index1;
@@ -77,11 +79,8 @@ public:
} }
/// todo: get this margin from the current physics / collision environment /// todo: get this margin from the current physics / collision environment
inline float GetManifoldMargin() const float GetManifoldMargin() const;
{
return 0.02f;
}
int GetCacheEntry(const ManifoldPoint& newPoint) const; int GetCacheEntry(const ManifoldPoint& newPoint) const;
void AddManifoldPoint( const ManifoldPoint& newPoint); void AddManifoldPoint( const ManifoldPoint& newPoint);

View File

@@ -175,6 +175,8 @@ m_collisionImpulse = 0.f;
input.m_maximumDistanceSquared = min0->GetMargin() + min1->GetMargin() + m_manifoldPtr->GetManifoldMargin(); input.m_maximumDistanceSquared = min0->GetMargin() + min1->GetMargin() + m_manifoldPtr->GetManifoldMargin();
input.m_maximumDistanceSquared*= input.m_maximumDistanceSquared; input.m_maximumDistanceSquared*= input.m_maximumDistanceSquared;
} }
input.m_maximumDistanceSquared = 1e30;//
input.m_transformA = body0->getCenterOfMassTransform(); input.m_transformA = body0->getCenterOfMassTransform();
input.m_transformB = body1->getCenterOfMassTransform(); input.m_transformB = body1->getCenterOfMassTransform();

View File

@@ -86,18 +86,15 @@ void ToiContactDispatcher::ReleaseManifold(PersistentManifold* manifold)
// //
// todo: this is random access, it can be walked 'cache friendly'! // todo: this is random access, it can be walked 'cache friendly'!
// //
void ToiContactDispatcher::SolveConstraints(float timeStep, int numIterations,int numRigidBodies) void ToiContactDispatcher::SolveConstraints(float timeStep, int numIterations,int numRigidBodies,IDebugDraw* debugDrawer)
{ {
int i; int i;
int numManifolds;
for (int islandId=0;islandId<numRigidBodies;islandId++) for (int islandId=0;islandId<numRigidBodies;islandId++)
{ {
numManifolds = 0;
PersistentManifold* manifolds[MAX_MANIFOLDS];
std::vector<PersistentManifold*> islandmanifold;
//int numSleeping = 0; //int numSleeping = 0;
@@ -116,16 +113,15 @@ void ToiContactDispatcher::SolveConstraints(float timeStep, int numIterations,in
allSleeping = false; allSleeping = false;
} }
manifolds[numManifolds] = manifold; islandmanifold.push_back(manifold);
numManifolds++;
} }
} }
if (allSleeping) if (allSleeping)
{ {
//tag all as 'ISLAND_SLEEPING' //tag all as 'ISLAND_SLEEPING'
for (i=0;i<numManifolds;i++) for (i=0;i<islandmanifold.size();i++)
{ {
PersistentManifold* manifold = manifolds[i]; PersistentManifold* manifold = islandmanifold[i];
if (((RigidBody*)manifold->GetBody0())) if (((RigidBody*)manifold->GetBody0()))
{ {
((RigidBody*)manifold->GetBody0())->SetActivationState( ISLAND_SLEEPING ); ((RigidBody*)manifold->GetBody0())->SetActivationState( ISLAND_SLEEPING );
@@ -140,9 +136,9 @@ void ToiContactDispatcher::SolveConstraints(float timeStep, int numIterations,in
{ {
//tag all as 'ISLAND_SLEEPING' //tag all as 'ISLAND_SLEEPING'
for (i=0;i<numManifolds;i++) for (i=0;i<islandmanifold.size();i++)
{ {
PersistentManifold* manifold = manifolds[i]; PersistentManifold* manifold = islandmanifold[i];
if (((RigidBody*)manifold->GetBody0())) if (((RigidBody*)manifold->GetBody0()))
{ {
if ( ((RigidBody*)manifold->GetBody0())->GetActivationState() == ISLAND_SLEEPING) if ( ((RigidBody*)manifold->GetBody0())->GetActivationState() == ISLAND_SLEEPING)
@@ -169,19 +165,8 @@ void ToiContactDispatcher::SolveConstraints(float timeStep, int numIterations,in
info.m_tau = 0.4f; info.m_tau = 0.4f;
info.m_restitution = 0.1f;//m_restitution; info.m_restitution = 0.1f;//m_restitution;
/*
int numManifolds = 0;
for (i=0;i<m_firstFreeManifold;i++) m_solver->SolveGroup( &islandmanifold[0], islandmanifold.size(),info,debugDrawer );
{
PersistentManifold* manifold = &m_manifolds[m_freeManifolds[i]];
//ASSERT(((RigidBody*)manifold->GetBody0()));
//ASSERT(((RigidBody*)manifold->GetBody1()));
manifolds[i] = manifold;
numManifolds++;
}
*/
m_solver->SolveGroup( manifolds, numManifolds,info );
} }
} }

View File

@@ -7,13 +7,13 @@
#include "BroadphaseCollision/BroadphaseProxy.h" #include "BroadphaseCollision/BroadphaseProxy.h"
class ConstraintSolver; class ConstraintSolver;
class IDebugDraw;
//island management //island management
#define ACTIVE_TAG 1 #define ACTIVE_TAG 1
#define ISLAND_SLEEPING 2 #define ISLAND_SLEEPING 2
#define WANTS_DEACTIVATION 3 #define WANTS_DEACTIVATION 3
#define MAX_MANIFOLDS 512
struct CollisionAlgorithmCreateFunc struct CollisionAlgorithmCreateFunc
{ {
@@ -40,8 +40,6 @@ class ToiContactDispatcher : public Dispatcher
std::vector<PersistentManifold*> m_manifoldsPtr; std::vector<PersistentManifold*> m_manifoldsPtr;
// PersistentManifold m_manifolds[MAX_MANIFOLDS];
// int m_freeManifolds[MAX_MANIFOLDS];
UnionFind m_unionFind; UnionFind m_unionFind;
ConstraintSolver* m_solver; ConstraintSolver* m_solver;
@@ -86,7 +84,7 @@ public:
// //
// todo: this is random access, it can be walked 'cache friendly'! // todo: this is random access, it can be walked 'cache friendly'!
// //
virtual void SolveConstraints(float timeStep, int numIterations,int numRigidBodies); virtual void SolveConstraints(float timeStep, int numIterations,int numRigidBodies,IDebugDraw* debugDrawer);
CollisionAlgorithm* FindAlgorithm(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1) CollisionAlgorithm* FindAlgorithm(BroadphaseProxy& proxy0,BroadphaseProxy& proxy1)

View File

@@ -16,6 +16,7 @@ class RigidBody;
struct ContactSolverInfo; struct ContactSolverInfo;
struct BroadphaseProxy; struct BroadphaseProxy;
class IDebugDraw;
/// ConstraintSolver provides solver interface /// ConstraintSolver provides solver interface
class ConstraintSolver class ConstraintSolver
@@ -25,7 +26,7 @@ public:
virtual ~ConstraintSolver() {} virtual ~ConstraintSolver() {}
virtual float SolveGroup(PersistentManifold** manifold,int numManifolds,const ContactSolverInfo& info) = 0; virtual float SolveGroup(PersistentManifold** manifold,int numManifolds,const ContactSolverInfo& info,class IDebugDraw* debugDrawer = 0) = 0;
}; };

View File

@@ -23,16 +23,29 @@ static SimdScalar ContactThreshold = -10.0f;
float useGlobalSettingContacts = false;//true; float useGlobalSettingContacts = false;//true;
SimdScalar contactDamping = 0.9f; SimdScalar contactDamping = 0.9f;
SimdScalar contactTau = .2f;//0.02f;//*0.02f; SimdScalar contactTau = .02f;//0.02f;//*0.02f;
SimdScalar restitutionCurve(SimdScalar rel_vel, SimdScalar restitution) SimdScalar restitutionCurve(SimdScalar rel_vel, SimdScalar restitution)
{ {
return restitution; return 0.f;
// return restitution * GEN_min(1.0f, rel_vel / ContactThreshold); // return restitution * GEN_min(1.0f, rel_vel / ContactThreshold);
} }
float MAX_FRICTION = 100.f;
SimdScalar calculateCombinedFriction(RigidBody& body0,RigidBody& body1)
{
SimdScalar friction = body0.getFriction() * body1.getFriction();
if (friction < 0.f)
friction = 0.f;
if (friction > MAX_FRICTION)
friction = MAX_FRICTION;
return friction;
}
void applyFrictionInContactPointOld(RigidBody& body1, const SimdVector3& pos1, void applyFrictionInContactPointOld(RigidBody& body1, const SimdVector3& pos1,
RigidBody& body2, const SimdVector3& pos2, RigidBody& body2, const SimdVector3& pos2,
const SimdVector3& normal,float normalImpulse, const SimdVector3& normal,float normalImpulse,
@@ -51,6 +64,8 @@ void applyFrictionInContactPointOld(RigidBody& body1, const SimdVector3& pos1,
SimdScalar rel_vel = normal.dot(vel); SimdScalar rel_vel = normal.dot(vel);
float combinedFriction = calculateCombinedFriction(body1,body2);
#define PER_CONTACT_FRICTION #define PER_CONTACT_FRICTION
#ifdef PER_CONTACT_FRICTION #ifdef PER_CONTACT_FRICTION
SimdVector3 lat_vel = vel - normal * rel_vel; SimdVector3 lat_vel = vel - normal * rel_vel;
@@ -63,7 +78,7 @@ void applyFrictionInContactPointOld(RigidBody& body1, const SimdVector3& pos1,
SimdVector3 temp2 = body2.getInvInertiaTensorWorld() * rel_pos2.cross(lat_vel); SimdVector3 temp2 = body2.getInvInertiaTensorWorld() * rel_pos2.cross(lat_vel);
SimdScalar frictionMaxImpulse = lat_rel_vel / SimdScalar frictionMaxImpulse = lat_rel_vel /
(body1.getInvMass() + body2.getInvMass() + lat_vel.dot(temp1.cross(rel_pos1) + temp2.cross(rel_pos2))); (body1.getInvMass() + body2.getInvMass() + lat_vel.dot(temp1.cross(rel_pos1) + temp2.cross(rel_pos2)));
SimdScalar frictionImpulse = (normalImpulse) * solverInfo.m_friction; SimdScalar frictionImpulse = (normalImpulse) * combinedFriction;
GEN_set_min(frictionImpulse,frictionMaxImpulse ); GEN_set_min(frictionImpulse,frictionMaxImpulse );
body1.applyImpulse(lat_vel * -frictionImpulse, rel_pos1); body1.applyImpulse(lat_vel * -frictionImpulse, rel_pos1);
@@ -129,7 +144,6 @@ void resolveSingleBilateral(RigidBody& body1, const SimdVector3& pos1,
SimdScalar massTerm = 1.f / (body1.getInvMass() + body2.getInvMass()); SimdScalar massTerm = 1.f / (body1.getInvMass() + body2.getInvMass());
float contactDamping = 0.9f;
impulse = - contactDamping * rel_vel * massTerm;//jacDiagABInv; impulse = - contactDamping * rel_vel * massTerm;//jacDiagABInv;
//SimdScalar velocityImpulse = -contactDamping * rel_vel * jacDiagABInv; //SimdScalar velocityImpulse = -contactDamping * rel_vel * jacDiagABInv;
@@ -167,9 +181,11 @@ float resolveSingleCollision(RigidBody& body1, const SimdVector3& pos1,
// if (rel_vel< 0.f)//-SIMD_EPSILON) // if (rel_vel< 0.f)//-SIMD_EPSILON)
// { // {
SimdScalar rest = restitutionCurve(rel_vel, solverInfo.m_restitution); float combinedRestitution = body1.getRestitution() * body2.getRestitution();
SimdScalar timeCorrection = 1.f;///timeStep; SimdScalar rest = restitutionCurve(rel_vel, combinedRestitution);
SimdScalar timeCorrection = 360.f*solverInfo.m_timeStep;
float damping = solverInfo.m_damping ; float damping = solverInfo.m_damping ;
float tau = solverInfo.m_tau; float tau = solverInfo.m_tau;
@@ -252,7 +268,9 @@ SimdScalar rel_vel;
// if (rel_vel< 0.f)//-SIMD_EPSILON) // if (rel_vel< 0.f)//-SIMD_EPSILON)
// { // {
SimdScalar rest = restitutionCurve(rel_vel, solverInfo.m_restitution); float combinedRestitution = body1.getRestitution() * body2.getRestitution();
SimdScalar rest = restitutionCurve(rel_vel, combinedRestitution);
// SimdScalar massTerm = 1.f / (body1.getInvMass() + body2.getInvMass()); // SimdScalar massTerm = 1.f / (body1.getInvMass() + body2.getInvMass());
SimdScalar timeCorrection = 0.5f / solverInfo.m_timeStep ; SimdScalar timeCorrection = 0.5f / solverInfo.m_timeStep ;
@@ -302,6 +320,8 @@ SimdScalar rel_vel;
SimdVector3 lat_vel = vel - normal * rel_vel; SimdVector3 lat_vel = vel - normal * rel_vel;
SimdScalar lat_rel_vel = lat_vel.length(); SimdScalar lat_rel_vel = lat_vel.length();
float combinedFriction = calculateCombinedFriction(body1,body2);
if (lat_rel_vel > SIMD_EPSILON) if (lat_rel_vel > SIMD_EPSILON)
{ {
lat_vel /= lat_rel_vel; lat_vel /= lat_rel_vel;
@@ -310,7 +330,7 @@ SimdScalar rel_vel;
friction_impulse = lat_rel_vel / friction_impulse = lat_rel_vel /
(body1.getInvMass() + body2.getInvMass() + lat_vel.dot(temp1.cross(rel_pos1) + temp2.cross(rel_pos2))); (body1.getInvMass() + body2.getInvMass() + lat_vel.dot(temp1.cross(rel_pos1) + temp2.cross(rel_pos2)));
SimdScalar normal_impulse = (penetrationImpulse+ SimdScalar normal_impulse = (penetrationImpulse+
velocityImpulse) * solverInfo.m_friction; velocityImpulse) * combinedFriction;
GEN_set_min(friction_impulse, normal_impulse); GEN_set_min(friction_impulse, normal_impulse);
body1.applyImpulse(lat_vel * -friction_impulse, rel_pos1); body1.applyImpulse(lat_vel * -friction_impulse, rel_pos1);

View File

@@ -19,6 +19,8 @@
#include "Dynamics/BU_Joint.h" #include "Dynamics/BU_Joint.h"
#include "Dynamics/ContactJoint.h" #include "Dynamics/ContactJoint.h"
#include "IDebugDraw.h"
#define USE_SOR_SOLVER #define USE_SOR_SOLVER
#include "SorLcp.h" #include "SorLcp.h"
@@ -41,8 +43,7 @@ class BU_Joint;
//see below //see below
int gCurBody = 0;
int gCurJoint= 0;
int ConvertBody(RigidBody* body,RigidBody** bodies,int& numBodies); int ConvertBody(RigidBody* body,RigidBody** bodies,int& numBodies);
void ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJoints, void ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJoints,
@@ -53,10 +54,10 @@ void ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJo
//iterative lcp and penalty method //iterative lcp and penalty method
float OdeConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int numManifolds,const ContactSolverInfo& infoGlobal) float OdeConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int numManifolds,const ContactSolverInfo& infoGlobal,IDebugDraw* debugDrawer)
{ {
gCurBody = 0; m_CurBody = 0;
gCurJoint = 0; m_CurJoint = 0;
float cfm = 1e-5f; float cfm = 1e-5f;
float erp = 0.2f; float erp = 0.2f;
@@ -77,7 +78,7 @@ float OdeConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int numM
{ {
body0 = ConvertBody((RigidBody*)manifold->GetBody0(),bodies,numBodies); body0 = ConvertBody((RigidBody*)manifold->GetBody0(),bodies,numBodies);
body1 = ConvertBody((RigidBody*)manifold->GetBody1(),bodies,numBodies); body1 = ConvertBody((RigidBody*)manifold->GetBody1(),bodies,numBodies);
ConvertConstraint(manifold,joints,numJoints,bodies,body0,body1); ConvertConstraint(manifold,joints,numJoints,bodies,body0,body1,debugDrawer);
} }
} }
@@ -112,7 +113,7 @@ void dRfromQ1 (dMatrix3 R, const dQuaternion q)
int ConvertBody(RigidBody* body,RigidBody** bodies,int& numBodies) int OdeConstraintSolver::ConvertBody(RigidBody* body,RigidBody** bodies,int& numBodies)
{ {
if (!body || (body->getInvMass() == 0.f) ) if (!body || (body->getInvMass() == 0.f) )
{ {
@@ -195,8 +196,8 @@ int ConvertBody(RigidBody* body,RigidBody** bodies,int& numBodies)
static ContactJoint gJointArray[MAX_JOINTS_1]; static ContactJoint gJointArray[MAX_JOINTS_1];
void ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJoints, void OdeConstraintSolver::ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJoints,
RigidBody** bodies,int _bodyId0,int _bodyId1) RigidBody** bodies,int _bodyId0,int _bodyId1,IDebugDraw* debugDrawer)
{ {
@@ -228,14 +229,21 @@ void ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJo
assert(bodyId0 >= 0); assert(bodyId0 >= 0);
SimdVector3 color(0,1,0);
for (i=0;i<numContacts;i++) for (i=0;i<numContacts;i++)
{ {
assert (gCurJoint < MAX_JOINTS_1); if (debugDrawer)
{
debugDrawer->DrawLine(manifold->GetContactPoint(i).m_positionWorldOnA,manifold->GetContactPoint(i).m_positionWorldOnB,color);
debugDrawer->DrawLine(manifold->GetContactPoint(i).m_positionWorldOnA,manifold->GetContactPoint(i).m_positionWorldOnB,color);
}
assert (m_CurJoint < MAX_JOINTS_1);
if (manifold->GetContactPoint(i).GetDistance() < 0.f) if (manifold->GetContactPoint(i).GetDistance() < 0.f)
{ {
ContactJoint* cont = new (&gJointArray[gCurJoint++]) ContactJoint( manifold ,i, swapBodies,body0,body1); ContactJoint* cont = new (&gJointArray[m_CurJoint++]) ContactJoint( manifold ,i, swapBodies,body0,body1);
cont->node[0].joint = cont; cont->node[0].joint = cont;
cont->node[0].body = bodyId0 >= 0 ? bodies[bodyId0] : 0; cont->node[0].body = bodyId0 >= 0 ? bodies[bodyId0] : 0;

View File

@@ -13,15 +13,28 @@
#include "ConstraintSolver.h" #include "ConstraintSolver.h"
class RigidBody;
class BU_Joint;
/// OdeConstraintSolver is one of the available solvers for Bullet dynamics framework
/// It uses the the unmodified version of quickstep solver from the open dynamics project
class OdeConstraintSolver : public ConstraintSolver class OdeConstraintSolver : public ConstraintSolver
{ {
private:
int m_CurBody;
int m_CurJoint;
int ConvertBody(RigidBody* body,RigidBody** bodies,int& numBodies);
void ConvertConstraint(PersistentManifold* manifold,BU_Joint** joints,int& numJoints,
RigidBody** bodies,int _bodyId0,int _bodyId1,IDebugDraw* debugDrawer);
public: public:
virtual ~OdeConstraintSolver() {} virtual ~OdeConstraintSolver() {}
virtual float SolveGroup(PersistentManifold** manifold,int numManifolds,const ContactSolverInfo& info); virtual float SolveGroup(PersistentManifold** manifold,int numManifolds,const ContactSolverInfo& info,IDebugDraw* debugDrawer = 0);
}; };

View File

@@ -13,7 +13,7 @@
#include "Dynamics/MassProps.h" #include "Dynamics/MassProps.h"
static RigidBody s_fixed(MassProps(0,SimdVector3(0.f,0.f,0.f)),0.f,0.f); static RigidBody s_fixed(MassProps(0,SimdVector3(0.f,0.f,0.f)),0.f,0.f,1.f,1.f);
Point2PointConstraint::Point2PointConstraint(): Point2PointConstraint::Point2PointConstraint():
m_rbA(s_fixed),m_rbB(s_fixed) m_rbA(s_fixed),m_rbB(s_fixed)

View File

@@ -16,6 +16,7 @@
#include "ContactSolverInfo.h" #include "ContactSolverInfo.h"
#include "Dynamics/BU_Joint.h" #include "Dynamics/BU_Joint.h"
#include "Dynamics/ContactJoint.h" #include "Dynamics/ContactJoint.h"
#include "IDebugDraw.h"
//debugging //debugging
bool doApplyImpulse = true; bool doApplyImpulse = true;
@@ -28,7 +29,7 @@ bool useImpulseFriction = true;//true;//false;
//iterative lcp and penalty method //iterative lcp and penalty method
float SimpleConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int numManifolds,const ContactSolverInfo& infoGlobal) float SimpleConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int numManifolds,const ContactSolverInfo& infoGlobal,IDebugDraw* debugDrawer)
{ {
ContactSolverInfo info = infoGlobal; ContactSolverInfo info = infoGlobal;
@@ -41,7 +42,7 @@ float SimpleConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int n
{ {
for (int j=0;j<numManifolds;j++) for (int j=0;j<numManifolds;j++)
{ {
Solve(manifoldPtr[j],info,i); Solve(manifoldPtr[j],info,i,debugDrawer);
} }
} }
return 0.f; return 0.f;
@@ -51,7 +52,7 @@ float SimpleConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int n
float penetrationResolveFactor = 0.9f; float penetrationResolveFactor = 0.9f;
float SimpleConstraintSolver::Solve(PersistentManifold* manifoldPtr, const ContactSolverInfo& info,int iter) float SimpleConstraintSolver::Solve(PersistentManifold* manifoldPtr, const ContactSolverInfo& info,int iter,IDebugDraw* debugDrawer)
{ {
RigidBody* body0 = (RigidBody*)manifoldPtr->GetBody0(); RigidBody* body0 = (RigidBody*)manifoldPtr->GetBody0();
@@ -73,6 +74,7 @@ float SimpleConstraintSolver::Solve(PersistentManifold* manifoldPtr, const Conta
{ {
const int numpoints = manifoldPtr->GetNumContacts(); const int numpoints = manifoldPtr->GetNumContacts();
SimdVector3 color(0,1,0);
for (int i=0;i<numpoints ;i++) for (int i=0;i<numpoints ;i++)
{ {
@@ -83,6 +85,10 @@ float SimpleConstraintSolver::Solve(PersistentManifold* manifoldPtr, const Conta
j=i; j=i;
ManifoldPoint& cp = manifoldPtr->GetContactPoint(j); ManifoldPoint& cp = manifoldPtr->GetContactPoint(j);
if (debugDrawer)
debugDrawer->DrawLine(cp.m_positionWorldOnA,cp.m_positionWorldOnB,color);
{ {

View File

@@ -12,17 +12,19 @@
#define SIMPLE_CONSTRAINT_SOLVER_H #define SIMPLE_CONSTRAINT_SOLVER_H
#include "ConstraintSolver.h" #include "ConstraintSolver.h"
class IDebugDraw;
/// SimpleConstraintSolver uses a Propagation Method
/// Applies impulses for combined restitution and penetration recovery and to simulate friction
class SimpleConstraintSolver : public ConstraintSolver class SimpleConstraintSolver : public ConstraintSolver
{ {
float Solve(PersistentManifold* manifold, const ContactSolverInfo& info,int iter); float Solve(PersistentManifold* manifold, const ContactSolverInfo& info,int iter,IDebugDraw* debugDrawer);
public: public:
virtual ~SimpleConstraintSolver() {} virtual ~SimpleConstraintSolver() {}
virtual float SolveGroup(PersistentManifold** manifold,int numManifolds,const ContactSolverInfo& info); virtual float SolveGroup(PersistentManifold** manifold,int numManifolds,const ContactSolverInfo& info, IDebugDraw* debugDrawer=0);
}; };

View File

@@ -15,7 +15,7 @@ m_body1(body1)
int m_numRows = 3; int m_numRows = 3;
float gContactFrictionFactor = 30.5f;//100.f;//1e30f;//2.9f; //float gContactFrictionFactor = 0.f;//12.f;//30.5f;//100.f;//1e30f;//2.9f;
@@ -149,6 +149,9 @@ void ContactJoint::GetInfo2(Info2 *info)
c2[0] = ccc2[0]; c2[0] = ccc2[0];
c2[1] = ccc2[1]; c2[1] = ccc2[1];
c2[2] = ccc2[2]; c2[2] = ccc2[2];
float friction = m_body0->getFriction() * m_body1->getFriction();
// first friction direction // first friction direction
if (m_numRows >= 2) if (m_numRows >= 2)
{ {
@@ -175,8 +178,9 @@ void ContactJoint::GetInfo2(Info2 *info)
// mode // mode
//1e30f //1e30f
info->lo[1] = -gContactFrictionFactor;//-j->contact.surface.mu;
info->hi[1] = gContactFrictionFactor;//j->contact.surface.mu; info->lo[1] = -friction;//-j->contact.surface.mu;
info->hi[1] = friction;//j->contact.surface.mu;
if (0)//j->contact.surface.mode & dContactApprox1_1) if (0)//j->contact.surface.mode & dContactApprox1_1)
info->findex[1] = 0; info->findex[1] = 0;
@@ -210,8 +214,8 @@ void ContactJoint::GetInfo2(Info2 *info)
//info->hi[2] = j->contact.surface.mu2; //info->hi[2] = j->contact.surface.mu2;
} }
else { else {
info->lo[2] = -gContactFrictionFactor; info->lo[2] = -friction;
info->hi[2] = gContactFrictionFactor; info->hi[2] = friction;
} }
if (0)//j->contact.surface.mode & dContactApprox1_2) if (0)//j->contact.surface.mode & dContactApprox1_2)

View File

@@ -7,7 +7,7 @@
float gRigidBodyDamping = 0.5f; float gRigidBodyDamping = 0.5f;
static int uniqueId = 0; static int uniqueId = 0;
RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdScalar angularDamping) RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdScalar angularDamping,SimdScalar friction,SimdScalar restitution)
: m_collisionShape(0), : m_collisionShape(0),
m_activationState1(1), m_activationState1(1),
m_hitFraction(1.f), m_hitFraction(1.f),
@@ -17,7 +17,9 @@ RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdSc
m_totalForce(0.0f, 0.0f, 0.0f), m_totalForce(0.0f, 0.0f, 0.0f),
m_totalTorque(0.0f, 0.0f, 0.0f), m_totalTorque(0.0f, 0.0f, 0.0f),
m_linearVelocity(0.0f, 0.0f, 0.0f), m_linearVelocity(0.0f, 0.0f, 0.0f),
m_angularVelocity(0.f,0.f,0.f) m_angularVelocity(0.f,0.f,0.f),
m_restitution(restitution),
m_friction(friction)
{ {
m_debugBodyId = uniqueId++; m_debugBodyId = uniqueId++;

View File

@@ -15,7 +15,7 @@ typedef SimdScalar dMatrix3[4*3];
class RigidBody { class RigidBody {
public: public:
RigidBody(const MassProps& massProps,SimdScalar linearDamping,SimdScalar angularDamping); RigidBody(const MassProps& massProps,SimdScalar linearDamping,SimdScalar angularDamping,SimdScalar friction,SimdScalar restitution);
void proceedToTransform(const SimdTransform& newTrans); void proceedToTransform(const SimdTransform& newTrans);
@@ -123,6 +123,22 @@ public:
int GetActivationState() const { return m_activationState1;} int GetActivationState() const { return m_activationState1;}
void SetActivationState(int newState); void SetActivationState(int newState);
void setRestitution(float rest)
{
m_restitution = rest;
}
float getRestitution() const
{
return m_restitution;
}
void setFriction(float frict)
{
m_friction = frict;
}
float getFriction() const
{
return m_friction;
}
private: private:
SimdTransform m_worldTransform; SimdTransform m_worldTransform;
@@ -141,6 +157,8 @@ private:
SimdScalar m_angularDamping; SimdScalar m_angularDamping;
SimdScalar m_inverseMass; SimdScalar m_inverseMass;
SimdScalar m_friction;
SimdScalar m_restitution;
CollisionShape* m_collisionShape; CollisionShape* m_collisionShape;

View File

@@ -7,7 +7,7 @@
class BP_Proxy; class BP_Proxy;
bool gEnableSleeping = true;//false;//true; bool gEnableSleeping = false;//false;//true;
#include "Dynamics/MassProps.h" #include "Dynamics/MassProps.h"
SimdVector3 startVel(0,0,0);//-10000); SimdVector3 startVel(0,0,0);//-10000);

View File

@@ -14,6 +14,7 @@
#include "ConstraintSolver/OdeConstraintSolver.h" #include "ConstraintSolver/OdeConstraintSolver.h"
#include "ConstraintSolver/SimpleConstraintSolver.h" #include "ConstraintSolver/SimpleConstraintSolver.h"
#include "IDebugDraw.h"
#include "CollisionDispatch/ToiContactDispatcher.h" #include "CollisionDispatch/ToiContactDispatcher.h"
@@ -32,7 +33,7 @@ bool useIslands = true;
//#include "BroadphaseCollision/QueryBox.h" //#include "BroadphaseCollision/QueryBox.h"
//todo: change this to allow dynamic registration of types! //todo: change this to allow dynamic registration of types!
unsigned long gNumIterations = 10; unsigned long gNumIterations = 1;
#ifdef WIN32 #ifdef WIN32
void DrawRasterizerLine(const float* from,const float* to,int color); void DrawRasterizerLine(const float* from,const float* to,int color);
@@ -47,6 +48,43 @@ void DrawRasterizerLine(const float* from,const float* to,int color);
static void DrawAabb(IDebugDraw* debugDrawer,const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)
{
SimdVector3 halfExtents = (to-from)* 0.5f;
SimdVector3 center = (to+from) *0.5f;
int i,j;
SimdVector3 edgecoord(1.f,1.f,1.f),pa,pb;
for (i=0;i<4;i++)
{
for (j=0;j<3;j++)
{
pa = SimdVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
edgecoord[2]*halfExtents[2]);
pa+=center;
int othercoord = j%3;
edgecoord[othercoord]*=-1.f;
pb = SimdVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
edgecoord[2]*halfExtents[2]);
pb+=center;
debugDrawer->DrawLine(pa,pb,color);
}
edgecoord = SimdVector3(-1.f,-1.f,-1.f);
if (i<3)
edgecoord[i]*=-1.f;
}
}
CcdPhysicsEnvironment::CcdPhysicsEnvironment(ToiContactDispatcher* dispatcher,BroadphaseInterface* bp) CcdPhysicsEnvironment::CcdPhysicsEnvironment(ToiContactDispatcher* dispatcher,BroadphaseInterface* bp)
:m_dispatcher(dispatcher), :m_dispatcher(dispatcher),
m_broadphase(bp), m_broadphase(bp),
@@ -276,10 +314,6 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
//m_scalingPropagated = true; //m_scalingPropagated = true;
} }
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.begin("integrate force");
#endif //EXTRA_PHYSICS_PROFILE
{ {
@@ -301,9 +335,6 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
} }
} }
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.end("integrate force");
#endif //EXTRA_PHYSICS_PROFILE
BroadphaseInterface* scene = m_broadphase; BroadphaseInterface* scene = m_broadphase;
@@ -321,33 +352,21 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
DispatcherInfo dispatchInfo; DispatcherInfo dispatchInfo;
dispatchInfo.m_timeStep = timeStep; dispatchInfo.m_timeStep = timeStep;
dispatchInfo.m_stepCount = 0; dispatchInfo.m_stepCount = 0;
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.begin("cd");
#endif //EXTRA_PHYSICS_PROFILE
scene->DispatchAllCollisionPairs(*m_dispatcher,dispatchInfo);///numsubstep,g); scene->DispatchAllCollisionPairs(*m_dispatcher,dispatchInfo);///numsubstep,g);
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.end("cd");
#endif //EXTRA_PHYSICS_PROFILE
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.begin("solver");
#endif //EXTRA_PHYSICS_PROFILE
int numRigidBodies = m_controllers.size(); int numRigidBodies = m_controllers.size();
UpdateActivationState(); UpdateActivationState();
//contacts //contacts
m_dispatcher->SolveConstraints(timeStep, gNumIterations ,numRigidBodies);
m_dispatcher->SolveConstraints(timeStep, gNumIterations ,numRigidBodies,m_debugDrawer);
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.end("solver");
#endif //EXTRA_PHYSICS_PROFILE
for (int g=0;g<numsubstep;g++) for (int g=0;g<numsubstep;g++)
{ {
@@ -402,10 +421,16 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
SimdPoint3 minAabb,maxAabb; SimdPoint3 minAabb,maxAabb;
CollisionShape* shapeinterface = ctrl->GetCollisionShape(); CollisionShape* shapeinterface = ctrl->GetCollisionShape();
shapeinterface->CalculateTemporalAabb(body->getCenterOfMassTransform(), shapeinterface->CalculateTemporalAabb(body->getCenterOfMassTransform(),
body->getLinearVelocity(),body->getAngularVelocity(), body->getLinearVelocity(),body->getAngularVelocity(),
timeStep,minAabb,maxAabb); timeStep,minAabb,maxAabb);
shapeinterface->GetAabb(body->getCenterOfMassTransform(),
minAabb,maxAabb);
BroadphaseProxy* bp = (BroadphaseProxy*) ctrl->m_broadphaseHandle; BroadphaseProxy* bp = (BroadphaseProxy*) ctrl->m_broadphaseHandle;
if (bp) if (bp)
@@ -413,8 +438,12 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
#ifdef WIN32 #ifdef WIN32
SimdVector3 color (1,0,0); SimdVector3 color (1,0,0);
if (m_debugDrawer) if (0)//m_debugDrawer)
m_debugDrawer->DrawLine(minAabb,maxAabb,color); {
//draw aabb
DrawAabb(m_debugDrawer,minAabb,maxAabb,color);
}
#endif #endif
scene->SetAabb(bp,minAabb,maxAabb); scene->SetAabb(bp,minAabb,maxAabb);
} }

View File

@@ -6,10 +6,6 @@
class CcdPhysicsController; class CcdPhysicsController;
#include "SimdVector3.h" #include "SimdVector3.h"
struct PHY_IPhysicsDebugDraw
{
virtual void DrawLine(const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)=0;
};
class Point2PointConstraint; class Point2PointConstraint;
@@ -20,6 +16,7 @@ class Dispatcher;
class Vehicle; class Vehicle;
class PersistentManifold; class PersistentManifold;
class BroadphaseInterface; class BroadphaseInterface;
class IDebugDraw;
/// Physics Environment takes care of stepping the simulation and is a container for physics entities. /// Physics Environment takes care of stepping the simulation and is a container for physics entities.
/// It stores rigidbodies,constraints, materials etc. /// It stores rigidbodies,constraints, materials etc.
@@ -28,7 +25,7 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
{ {
SimdVector3 m_gravity; SimdVector3 m_gravity;
BroadphaseInterface* m_broadphase; BroadphaseInterface* m_broadphase;
PHY_IPhysicsDebugDraw* m_debugDrawer; IDebugDraw* m_debugDrawer;
public: public:
CcdPhysicsEnvironment(ToiContactDispatcher* dispatcher=0, BroadphaseInterface* broadphase=0); CcdPhysicsEnvironment(ToiContactDispatcher* dispatcher=0, BroadphaseInterface* broadphase=0);
@@ -41,7 +38,7 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
/// Perform an integration step of duration 'timeStep'. /// Perform an integration step of duration 'timeStep'.
virtual void setDebugDrawer(PHY_IPhysicsDebugDraw* debugDrawer) virtual void setDebugDrawer(IDebugDraw* debugDrawer)
{ {
m_debugDrawer = debugDrawer; m_debugDrawer = debugDrawer;
} }

42
extern/bullet/LinearMath/IDebugDraw.h vendored Normal file
View File

@@ -0,0 +1,42 @@
/*
Copyright (c) 2005 Gino van den Bergen / Erwin Coumans <www.erwincoumans.com>
Permission is hereby granted, free of charge, to any person or organization
obtaining a copy of the software and accompanying documentation covered by
this license (the "Software") to use, reproduce, display, distribute,
execute, and transmit the Software, and to prepare derivative works of the
Software, and to permit third-parties to whom the Software is furnished to
do so, all subject to the following:
The copyright notices in the Software and this entire statement, including
the above license grant, this restriction and the following disclaimer,
must be included in all copies of the Software, in whole or in part, and
all derivative works of the Software, unless such copies or derivative
works are solely in the form of machine-executable object code generated by
a source language processor.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT
SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE
FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,
ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
DEALINGS IN THE SOFTWARE.
*/
#ifndef IDEBUG_DRAW__H
#define IDEBUG_DRAW__H
#include "SimdVector3.h"
class IDebugDraw
{
public:
virtual void DrawLine(const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)=0;
virtual void SetDebugMode(int debugMode) =0;
};
#endif //IDEBUG_DRAW__H

View File

@@ -173,15 +173,32 @@ static struct Scene *GetSceneForName2(struct Main *maggie, const STR_String& sce
#include "KX_PythonInit.h" #include "KX_PythonInit.h"
#ifdef USE_BULLET #ifdef USE_BULLET
struct BlenderDebugDraw : public PHY_IPhysicsDebugDraw #include "IDebugDraw.h"
struct BlenderDebugDraw : public IDebugDraw
{ {
BlenderDebugDraw () :
m_debugMode(0)
{
}
int m_debugMode;
virtual void DrawLine(const SimdVector3& from,const SimdVector3& to,const SimdVector3& color) virtual void DrawLine(const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)
{ {
MT_Vector3 kxfrom(from[0],from[1],from[2]); if (m_debugMode == 1)
MT_Vector3 kxto(to[0],to[1],to[2]); {
MT_Vector3 kxcolor(color[0],color[1],color[2]); MT_Vector3 kxfrom(from[0],from[1],from[2]);
MT_Vector3 kxto(to[0],to[1],to[2]);
MT_Vector3 kxcolor(color[0],color[1],color[2]);
KX_RasterizerDrawDebugLine(kxfrom,kxto,kxcolor); KX_RasterizerDrawDebugLine(kxfrom,kxto,kxcolor);
}
}
virtual void SetDebugMode(int debugMode)
{
m_debugMode = debugMode;
} }
}; };

View File

@@ -133,7 +133,7 @@ void KX_ConvertSumoObject( KX_GameObject* gameobj,
smmaterial->m_fh_normal = kxmaterial->m_fh_normal; smmaterial->m_fh_normal = kxmaterial->m_fh_normal;
smmaterial->m_fh_spring = kxmaterial->m_fh_spring; smmaterial->m_fh_spring = kxmaterial->m_fh_spring;
smmaterial->m_friction = kxmaterial->m_friction; smmaterial->m_friction = kxmaterial->m_friction;
smmaterial->m_restitution = kxmaterial->m_restitution; smmaterial->m_restitution = 0.f;//kxmaterial->m_restitution;
SumoPhysicsEnvironment* sumoEnv = SumoPhysicsEnvironment* sumoEnv =
(SumoPhysicsEnvironment*)kxscene->GetPhysicsEnvironment(); (SumoPhysicsEnvironment*)kxscene->GetPhysicsEnvironment();
@@ -911,9 +911,8 @@ void KX_ConvertBulletObject( class KX_GameObject* gameobj,
halfExtents /= 2.f; halfExtents /= 2.f;
SimdVector3 he (halfExtents[0]-CONVEX_DISTANCE_MARGIN ,halfExtents[1]-CONVEX_DISTANCE_MARGIN ,halfExtents[2]-CONVEX_DISTANCE_MARGIN ); //todo: do this conversion internally !
he = he.absolute(); SimdVector3 he (halfExtents[0],halfExtents[1],halfExtents[2]);
bm = new BoxShape(he); bm = new BoxShape(he);
bm->CalculateLocalInertia(ci.m_mass,ci.m_localInertiaTensor); bm->CalculateLocalInertia(ci.m_mass,ci.m_localInertiaTensor);
@@ -957,7 +956,7 @@ void KX_ConvertBulletObject( class KX_GameObject* gameobj,
if (bm) if (bm)
{ {
bm->CalculateLocalInertia(ci.m_mass,ci.m_localInertiaTensor); bm->CalculateLocalInertia(ci.m_mass,ci.m_localInertiaTensor);
bm->SetMargin(0.f); bm->SetMargin(0.05f);
} }
break; break;
} }
@@ -1005,8 +1004,8 @@ void KX_ConvertBulletObject( class KX_GameObject* gameobj,
ci.m_restitution = smmaterial->m_restitution; ci.m_restitution = smmaterial->m_restitution;
ci.m_linearDamping = shapeprops->m_lin_drag; ci.m_linearDamping = 0.5;//shapeprops->m_lin_drag;
ci.m_angularDamping = shapeprops->m_ang_drag; ci.m_angularDamping = 0.5f;//shapeprops->m_ang_drag;
KX_BulletPhysicsController* physicscontroller = new KX_BulletPhysicsController(ci,dyna); KX_BulletPhysicsController* physicscontroller = new KX_BulletPhysicsController(ci,dyna);
env->addCcdPhysicsController( physicscontroller); env->addCcdPhysicsController( physicscontroller);

View File

@@ -62,7 +62,7 @@
#include "KX_PyMath.h" #include "KX_PyMath.h"
#include "SumoPhysicsEnvironment.h" #include "PHY_IPhysicsEnvironment.h"
// FIXME: Enable for access to blender python modules. This is disabled because // FIXME: Enable for access to blender python modules. This is disabled because
// python has dependencies on a lot of other modules and is a pain to link. // python has dependencies on a lot of other modules and is a pain to link.
//#define USE_BLENDER_PYTHON //#define USE_BLENDER_PYTHON
@@ -227,6 +227,22 @@ static PyObject* gPySetPhysicsTicRate(PyObject*,
return NULL; return NULL;
} }
static PyObject* gPySetPhysicsDebug(PyObject*,
PyObject* args,
PyObject*)
{
int debugMode;
if (PyArg_ParseTuple(args, "i", &debugMode))
{
PHY_GetActiveEnvironment()->setDebugMode(debugMode);
Py_Return;
}
return NULL;
}
static PyObject* gPyGetPhysicsTicRate(PyObject*, PyObject*, PyObject*) static PyObject* gPyGetPhysicsTicRate(PyObject*, PyObject*, PyObject*)
{ {
return PyFloat_FromDouble(PHY_GetActiveEnvironment()->getFixedTimeStep()); return PyFloat_FromDouble(PHY_GetActiveEnvironment()->getFixedTimeStep());

View File

@@ -31,7 +31,7 @@ CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
MassProps mp(ci.m_mass, ci.m_localInertiaTensor); MassProps mp(ci.m_mass, ci.m_localInertiaTensor);
m_body = new RigidBody(mp,0,0); m_body = new RigidBody(mp,0,0,ci.m_friction,ci.m_restitution);
m_broadphaseHandle = ci.m_broadphaseHandle; m_broadphaseHandle = ci.m_broadphaseHandle;
@@ -44,12 +44,10 @@ CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
m_body->setMassProps(ci.m_mass, ci.m_localInertiaTensor); m_body->setMassProps(ci.m_mass, ci.m_localInertiaTensor);
m_body->setGravity( ci.m_gravity); m_body->setGravity( ci.m_gravity);
m_friction = ci.m_friction;
m_restitution = ci.m_restitution;
m_body->setDamping(ci.m_linearDamping, ci.m_angularDamping); m_body->setDamping(ci.m_linearDamping, ci.m_angularDamping);
m_body->setCenterOfMassTransform( trans ); m_body->setCenterOfMassTransform( trans );
#ifdef WIN32 #ifdef WIN32

View File

@@ -15,7 +15,6 @@ struct CcdConstructionInfo
CcdConstructionInfo() CcdConstructionInfo()
: m_gravity(0,0,0), : m_gravity(0,0,0),
m_mass(0.f), m_mass(0.f),
m_friction(0.1f),
m_restitution(0.1f), m_restitution(0.1f),
m_linearDamping(0.1f), m_linearDamping(0.1f),
m_angularDamping(0.1f), m_angularDamping(0.1f),
@@ -27,9 +26,8 @@ struct CcdConstructionInfo
SimdVector3 m_localInertiaTensor; SimdVector3 m_localInertiaTensor;
SimdVector3 m_gravity; SimdVector3 m_gravity;
SimdScalar m_mass; SimdScalar m_mass;
SimdScalar m_friction;
SimdScalar m_restitution; SimdScalar m_restitution;
SimdScalar m_friction;
SimdScalar m_linearDamping; SimdScalar m_linearDamping;
SimdScalar m_angularDamping; SimdScalar m_angularDamping;
void* m_broadphaseHandle; void* m_broadphaseHandle;
@@ -54,8 +52,6 @@ class CcdPhysicsController : public PHY_IPhysicsController
int m_collisionDelay; int m_collisionDelay;
SimdScalar m_friction;
SimdScalar m_restitution;
void* m_broadphaseHandle; void* m_broadphaseHandle;
CcdPhysicsController (const CcdConstructionInfo& ci); CcdPhysicsController (const CcdConstructionInfo& ci);

View File

@@ -14,6 +14,7 @@
#include "ConstraintSolver/OdeConstraintSolver.h" #include "ConstraintSolver/OdeConstraintSolver.h"
#include "ConstraintSolver/SimpleConstraintSolver.h" #include "ConstraintSolver/SimpleConstraintSolver.h"
#include "IDebugDraw.h"
#include "CollisionDispatch/ToiContactDispatcher.h" #include "CollisionDispatch/ToiContactDispatcher.h"
@@ -32,7 +33,7 @@ bool useIslands = true;
//#include "BroadphaseCollision/QueryBox.h" //#include "BroadphaseCollision/QueryBox.h"
//todo: change this to allow dynamic registration of types! //todo: change this to allow dynamic registration of types!
unsigned long gNumIterations = 10; unsigned long gNumIterations = 20;
#ifdef WIN32 #ifdef WIN32
void DrawRasterizerLine(const float* from,const float* to,int color); void DrawRasterizerLine(const float* from,const float* to,int color);
@@ -48,7 +49,7 @@ void DrawRasterizerLine(const float* from,const float* to,int color);
static void DrawAabb(PHY_IPhysicsDebugDraw* debugDrawer,const SimdVector3& from,const SimdVector3& to,const SimdVector3& color) static void DrawAabb(IDebugDraw* debugDrawer,const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)
{ {
SimdVector3 halfExtents = (to-from)* 0.5f; SimdVector3 halfExtents = (to-from)* 0.5f;
SimdVector3 center = (to+from) *0.5f; SimdVector3 center = (to+from) *0.5f;
@@ -313,10 +314,6 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
//m_scalingPropagated = true; //m_scalingPropagated = true;
} }
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.begin("integrate force");
#endif //EXTRA_PHYSICS_PROFILE
{ {
@@ -338,9 +335,6 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
} }
} }
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.end("integrate force");
#endif //EXTRA_PHYSICS_PROFILE
BroadphaseInterface* scene = m_broadphase; BroadphaseInterface* scene = m_broadphase;
@@ -358,33 +352,22 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
DispatcherInfo dispatchInfo; DispatcherInfo dispatchInfo;
dispatchInfo.m_timeStep = timeStep; dispatchInfo.m_timeStep = timeStep;
dispatchInfo.m_stepCount = 0; dispatchInfo.m_stepCount = 0;
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.begin("cd");
#endif //EXTRA_PHYSICS_PROFILE
scene->DispatchAllCollisionPairs(*m_dispatcher,dispatchInfo);///numsubstep,g); scene->DispatchAllCollisionPairs(*m_dispatcher,dispatchInfo);///numsubstep,g);
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.end("cd");
#endif //EXTRA_PHYSICS_PROFILE
#ifdef EXTRA_PHYSICS_PROFILE
cpuProfile.begin("solver");
#endif //EXTRA_PHYSICS_PROFILE
int numRigidBodies = m_controllers.size(); int numRigidBodies = m_controllers.size();
UpdateActivationState(); UpdateActivationState();
//contacts //contacts
m_dispatcher->SolveConstraints(timeStep, gNumIterations ,numRigidBodies);
#ifdef EXTRA_PHYSICS_PROFILE m_dispatcher->SolveConstraints(timeStep, gNumIterations ,numRigidBodies,m_debugDrawer);
cpuProfile.end("solver");
#endif //EXTRA_PHYSICS_PROFILE
for (int g=0;g<numsubstep;g++) for (int g=0;g<numsubstep;g++)
{ {
@@ -558,6 +541,29 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
return true; return true;
} }
void CcdPhysicsEnvironment::setDebugMode(int debugMode)
{
if (debugMode > 10)
{
if (m_dispatcher)
delete m_dispatcher;
if (debugMode == 11)
{
SimpleConstraintSolver* solver= new SimpleConstraintSolver();
m_dispatcher = new ToiContactDispatcher(solver);
} else
{
OdeConstraintSolver* solver = new OdeConstraintSolver();
m_dispatcher = new ToiContactDispatcher(solver);
}
}
if (m_debugDrawer){
m_debugDrawer->SetDebugMode(debugMode);
}
}
void CcdPhysicsEnvironment::SyncMotionStates(float timeStep) void CcdPhysicsEnvironment::SyncMotionStates(float timeStep)
{ {
std::vector<CcdPhysicsController*>::iterator i; std::vector<CcdPhysicsController*>::iterator i;

View File

@@ -6,10 +6,6 @@
class CcdPhysicsController; class CcdPhysicsController;
#include "SimdVector3.h" #include "SimdVector3.h"
struct PHY_IPhysicsDebugDraw
{
virtual void DrawLine(const SimdVector3& from,const SimdVector3& to,const SimdVector3& color)=0;
};
class Point2PointConstraint; class Point2PointConstraint;
@@ -20,6 +16,7 @@ class Dispatcher;
class Vehicle; class Vehicle;
class PersistentManifold; class PersistentManifold;
class BroadphaseInterface; class BroadphaseInterface;
class IDebugDraw;
/// Physics Environment takes care of stepping the simulation and is a container for physics entities. /// Physics Environment takes care of stepping the simulation and is a container for physics entities.
/// It stores rigidbodies,constraints, materials etc. /// It stores rigidbodies,constraints, materials etc.
@@ -28,7 +25,7 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
{ {
SimdVector3 m_gravity; SimdVector3 m_gravity;
BroadphaseInterface* m_broadphase; BroadphaseInterface* m_broadphase;
PHY_IPhysicsDebugDraw* m_debugDrawer; IDebugDraw* m_debugDrawer;
public: public:
CcdPhysicsEnvironment(ToiContactDispatcher* dispatcher=0, BroadphaseInterface* broadphase=0); CcdPhysicsEnvironment(ToiContactDispatcher* dispatcher=0, BroadphaseInterface* broadphase=0);
@@ -41,7 +38,7 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
/// Perform an integration step of duration 'timeStep'. /// Perform an integration step of duration 'timeStep'.
virtual void setDebugDrawer(PHY_IPhysicsDebugDraw* debugDrawer) virtual void setDebugDrawer(IDebugDraw* debugDrawer)
{ {
m_debugDrawer = debugDrawer; m_debugDrawer = debugDrawer;
} }
@@ -53,8 +50,11 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
virtual bool proceedDeltaTime(double curTime,float timeStep); virtual bool proceedDeltaTime(double curTime,float timeStep);
virtual void setFixedTimeStep(bool useFixedTimeStep,float fixedTimeStep){}; virtual void setFixedTimeStep(bool useFixedTimeStep,float fixedTimeStep){};
//returns 0.f if no fixed timestep is used //returns 0.f if no fixed timestep is used
virtual float getFixedTimeStep(){ return 0.f;}; virtual float getFixedTimeStep(){ return 0.f;};
virtual void setDebugMode(int debugMode);
virtual void setGravity(float x,float y,float z); virtual void setGravity(float x,float y,float z);
virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type, virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type,
@@ -116,6 +116,7 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
bool m_scalingPropagated; bool m_scalingPropagated;
}; };
#endif //CCDPHYSICSENVIRONMENT #endif //CCDPHYSICSENVIRONMENT

View File

@@ -51,7 +51,7 @@ class PHY_IPhysicsEnvironment
//returns 0.f if no fixed timestep is used //returns 0.f if no fixed timestep is used
virtual float getFixedTimeStep()=0; virtual float getFixedTimeStep()=0;
virtual void setDebugMode(int debugMode) {}
virtual void setGravity(float x,float y,float z)=0; virtual void setGravity(float x,float y,float z)=0;
virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type, virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type,