improved some Bullet Dynamics, related to friction/contact constraints.

This commit is contained in:
Erwin Coumans 2006-04-04 22:26:11 +00:00
parent 21ca6c3db8
commit 9d41401d93
14 changed files with 125 additions and 92 deletions

@ -21,7 +21,7 @@ subject to the following restrictions:
#include "SimdTransform.h"
#include "SimdMatrix3x3.h"
#include <vector>
#include "CollisionShapes/CollisionMargin.h"
SimpleBroadphase::SimpleBroadphase(int maxProxies,int maxOverlap)
:m_firstFreeProxy(0),

@ -377,14 +377,6 @@
RelativePath=".\CollisionShapes\ConvexShape.h"
>
</File>
<File
RelativePath=".\CollisionShapes\ConvexTriangleCallback.cpp"
>
</File>
<File
RelativePath=".\CollisionShapes\ConvexTriangleCallback.h"
>
</File>
<File
RelativePath=".\CollisionShapes\CylinderShape.cpp"
>
@ -654,10 +646,6 @@
>
</File>
</Filter>
<File
RelativePath=".\VTune\Bullet3ContinuousCollision.vpj"
>
</File>
<File
RelativePath=".\CollisionShapes\BvhTriangleMeshShape.cpp"
>

@ -23,6 +23,11 @@ void CollisionObject::SetActivationState(int newState)
m_activationState1 = newState;
}
void CollisionObject::ForceActivationState(int newState)
{
m_activationState1 = newState;
}
void CollisionObject::activate()
{
SetActivationState(1);

@ -76,6 +76,8 @@ struct CollisionObject
void SetActivationState(int newState);
void ForceActivationState(int newState);
void activate();

@ -74,7 +74,7 @@ void ConvexTriangleCallback::ProcessTriangle(SimdVector3* triangle)
input.m_maximumDistanceSquared = 1e30f;//?
gjkDetector.GetClosestPoints(input,output,0);
gjkDetector.GetClosestPoints(input,output);
}

@ -75,8 +75,8 @@ class ManifoldPoint
void CopyPersistentInformation(const ManifoldPoint& otherPoint)
{
m_appliedImpulse = otherPoint.m_appliedImpulse;
m_accumulatedTangentImpulse0 = 0.f;//otherPoint.m_accumulatedTangentImpulse0;
m_accumulatedTangentImpulse1 = 0.f;//otherPoint.m_accumulatedTangentImpulse1;
m_accumulatedTangentImpulse0 = otherPoint.m_accumulatedTangentImpulse0;
m_accumulatedTangentImpulse1 = otherPoint.m_accumulatedTangentImpulse1;
m_prevAppliedImpulse = otherPoint.m_prevAppliedImpulse;
m_lifeTime = otherPoint.m_lifeTime;

@ -162,14 +162,6 @@
RelativePath=".\ConstraintSolver\ContactSolverInfo.h"
>
</File>
<File
RelativePath=".\ConstraintSolver\HingeConstraint.cpp"
>
</File>
<File
RelativePath=".\ConstraintSolver\HingeConstraint.h"
>
</File>
<File
RelativePath=".\ConstraintSolver\JacobianEntry.h"
>

@ -42,7 +42,7 @@ SimdScalar calculateCombinedFriction(RigidBody& body0,RigidBody& body1)
{
SimdScalar friction = body0.getFriction() * body1.getFriction();
const SimdScalar MAX_FRICTION = 1.f;
const SimdScalar MAX_FRICTION = 10.f;
if (friction < -MAX_FRICTION)
friction = -MAX_FRICTION;
if (friction > MAX_FRICTION)
@ -102,7 +102,7 @@ void resolveSingleBilateral(RigidBody& body1, const SimdVector3& pos1,
#endif
}
float allowedPenetration = 0.0f;
//velocity + friction
@ -153,10 +153,9 @@ float resolveSingleCollision(
//printf("dist=%f\n",distance);
float clipDist = distance + allowedPenetration;
float dist = (clipDist > 0.f) ? 0.f : clipDist;
//distance = 0.f;
SimdScalar positionalError = Kcor *-dist;
SimdScalar positionalError = Kcor *-distance;
//jacDiagABInv;
SimdScalar velocityError = -(1.0f + restitution) * rel_vel;// * damping;
@ -197,7 +196,7 @@ float resolveSingleFriction(
float combinedFriction = calculateCombinedFriction(body1,body2);
SimdScalar limit = contactPoint.m_appliedImpulse * combinedFriction;
if (contactPoint.m_appliedImpulse>0.f)
//if (contactPoint.m_appliedImpulse>0.f)
//friction
{
//apply friction in the 2 tangential directions

@ -22,7 +22,7 @@ struct ContactSolverInfo
inline ContactSolverInfo()
{
m_tau = 0.4f;
m_tau = 0.6f;
m_damping = 1.0f;
m_friction = 0.3f;
m_restitution = 0.f;

@ -67,8 +67,7 @@ void Point2PointConstraint::SolveConstraint(SimdScalar timeStep)
SimdVector3 normal(0,0,0);
SimdScalar tau = 0.3f;
SimdScalar damping = 1.f;
// SimdVector3 angvelA = m_rbA.getCenterOfMassTransform().getBasis().transpose() * m_rbA.getAngularVelocity();
// SimdVector3 angvelB = m_rbB.getCenterOfMassTransform().getBasis().transpose() * m_rbB.getAngularVelocity();
@ -98,7 +97,7 @@ void Point2PointConstraint::SolveConstraint(SimdScalar timeStep)
//positional error (zeroth order error)
SimdScalar depth = -(pivotAInW - pivotBInW).dot(normal); //this is the error projected on the normal
SimdScalar impulse = depth*tau/timeStep * jacDiagABInv - damping * rel_vel * jacDiagABInv * damping;
SimdScalar impulse = depth*m_setting.m_tau/timeStep * jacDiagABInv - m_setting.m_damping * rel_vel * jacDiagABInv;
SimdVector3 impulse_vector = normal * impulse;
m_rbA.applyImpulse(impulse_vector, pivotAInW - m_rbA.getCenterOfMassPosition());

@ -23,6 +23,16 @@ subject to the following restrictions:
class RigidBody;
struct ConstraintSetting
{
ConstraintSetting() :
m_tau(0.3f),
m_damping(1.f)
{
}
float m_tau;
float m_damping;
};
/// point to point constraint between two rigidbodies each with a pivotpoint that descibes the 'ballsocket' location in local space
class Point2PointConstraint : public TypedConstraint
@ -33,8 +43,11 @@ class Point2PointConstraint : public TypedConstraint
SimdVector3 m_pivotInB;
public:
ConstraintSetting m_setting;
Point2PointConstraint(RigidBody& rbA,RigidBody& rbB, const SimdVector3& pivotInA,const SimdVector3& pivotInB);
Point2PointConstraint(RigidBody& rbA,const SimdVector3& pivotInA);
@ -48,7 +61,15 @@ public:
void UpdateRHS(SimdScalar timeStep);
void SetPivotA(const SimdVector3& pivotA)
{
m_pivotInA = pivotA;
}
void SetPivotB(const SimdVector3& pivotB)
{
m_pivotInB = pivotB;
}

@ -43,25 +43,25 @@ float SimpleConstraintSolver::SolveGroup(PersistentManifold** manifoldPtr, int n
for (j=0;j<numManifolds;j++)
{
int k=j;
if (i&&1)
if (i&1)
k=numManifolds-j-1;
Solve(manifoldPtr[k],info,i,debugDrawer);
}
for (j=0;j<numManifolds;j++)
{
int k = j;
if (i&&1)
k=numManifolds-j-1;
SolveFriction(manifoldPtr[k],info,i,debugDrawer);
}
}
//now solve the friction
for (int i = 0;i<numiter;i++)
{
int j;
for (j=0;j<numManifolds;j++)
{
int k = j;
if (i&1)
k=numManifolds-j-1;
SolveFriction(manifoldPtr[k],info,i,debugDrawer);
}
}
return 0.f;
@ -108,14 +108,16 @@ float SimpleConstraintSolver::Solve(PersistentManifold* manifoldPtr, const Conta
cp.m_jacDiagABInv = 1.f / jacDiagAB;
//for friction
cp.m_prevAppliedImpulse = cp.m_appliedImpulse;
float relaxation = info.m_damping;
cp.m_appliedImpulse *= relaxation;
//for friction
cp.m_prevAppliedImpulse = cp.m_appliedImpulse;
//re-calculate friction direction every frame, todo: check if this is really needed
SimdPlaneSpace1(cp.m_normalWorldOnB,cp.m_frictionWorldTangential0,cp.m_frictionWorldTangential1);
#define NO_FRICTION_WARMSTART 1
#ifdef NO_FRICTION_WARMSTART
cp.m_accumulatedTangentImpulse0 = 0.f;
@ -161,7 +163,7 @@ float SimpleConstraintSolver::Solve(PersistentManifold* manifoldPtr, const Conta
j=i;
ManifoldPoint& cp = manifoldPtr->GetContactPoint(j);
if (cp.GetDistance() <= 0.f)
if (cp.GetDistance() <= 0.f)
{
if (iter == 0)
@ -204,9 +206,11 @@ float SimpleConstraintSolver::SolveFriction(PersistentManifold* manifoldPtr, con
{
int j=i;
//if (iter % 2)
// j = numpoints-1-i;
ManifoldPoint& cp = manifoldPtr->GetContactPoint(j);
if (cp.GetDistance() <= 0.f)
if (cp.GetDistance() <= 0.f)
{
resolveSingleFriction(

@ -452,9 +452,12 @@ bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep)
if (!SimdFuzzyZero(timeStep))
{
//Blender runs 30hertz, so subdivide so we get 60 hertz
#ifdef SPLIT_TIMESTEP
proceedDeltaTimeOneStep(0.5f*timeStep);
proceedDeltaTimeOneStep(0.5f*timeStep);
#else
proceedDeltaTimeOneStep(timeStep);
#endif
} else
{
//todo: interpolate
@ -542,7 +545,48 @@ bool CcdPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
//contacts
struct InplaceSolverIslandCallback : public CollisionDispatcher::IslandCallback
//solve the regular constraints (point 2 point, hinge, etc)
for (int g=0;g<numsubstep;g++)
{
//
// constraint solving
//
int i;
int numPoint2Point = m_p2pConstraints.size();
//point to point constraints
for (i=0;i< numPoint2Point ; i++ )
{
Point2PointConstraint* p2p = m_p2pConstraints[i];
p2p->BuildJacobian();
p2p->SolveConstraint( timeStep );
}
}
//solve the vehicles
#ifdef NEW_BULLET_VEHICLE_SUPPORT
//vehicles
int numVehicles = m_wrapperVehicles.size();
for (int i=0;i<numVehicles;i++)
{
WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
RaycastVehicle* vehicle = wrapperVehicle->GetVehicle();
vehicle->UpdateVehicle( timeStep);
}
#endif //NEW_BULLET_VEHICLE_SUPPORT
struct InplaceSolverIslandCallback : public CollisionDispatcher::IslandCallback
{
ContactSolverInfo& m_solverInfo;
@ -578,47 +622,10 @@ bool CcdPhysicsEnvironment::proceedDeltaTimeOneStep(float timeStep)
m_solver,
m_debugDrawer);
/// solve all the contact points and contact friction
GetDispatcher()->BuildAndProcessIslands(numRigidBodies,&solverCallback);
for (int g=0;g<numsubstep;g++)
{
//
// constraint solving
//
int i;
int numPoint2Point = m_p2pConstraints.size();
//point to point constraints
for (i=0;i< numPoint2Point ; i++ )
{
Point2PointConstraint* p2p = m_p2pConstraints[i];
p2p->BuildJacobian();
p2p->SolveConstraint( timeStep );
}
}
#ifdef NEW_BULLET_VEHICLE_SUPPORT
//vehicles
int numVehicles = m_wrapperVehicles.size();
for (int i=0;i<numVehicles;i++)
{
WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
RaycastVehicle* vehicle = wrapperVehicle->GetVehicle();
vehicle->UpdateVehicle( timeStep);
}
#endif //NEW_BULLET_VEHICLE_SUPPORT
{
@ -943,13 +950,13 @@ void CcdPhysicsEnvironment::setGravity(float x,float y,float z)
#ifdef NEW_BULLET_VEHICLE_SUPPORT
class BlenderVehicleRaycaster : public VehicleRaycaster
class DefaultVehicleRaycaster : public VehicleRaycaster
{
CcdPhysicsEnvironment* m_physEnv;
PHY_IPhysicsController* m_chassis;
public:
BlenderVehicleRaycaster(CcdPhysicsEnvironment* physEnv,PHY_IPhysicsController* chassis):
DefaultVehicleRaycaster(CcdPhysicsEnvironment* physEnv,PHY_IPhysicsController* chassis):
m_physEnv(physEnv),
m_chassis(chassis)
{
@ -1061,7 +1068,7 @@ int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl
{
RaycastVehicle::VehicleTuning* tuning = new RaycastVehicle::VehicleTuning();
RigidBody* chassis = rb0;
BlenderVehicleRaycaster* raycaster = new BlenderVehicleRaycaster(this,ctrl0);
DefaultVehicleRaycaster* raycaster = new DefaultVehicleRaycaster(this,ctrl0);
RaycastVehicle* vehicle = new RaycastVehicle(*tuning,chassis,raycaster);
WrapperVehicle* wrapperVehicle = new WrapperVehicle(vehicle,ctrl0);
m_wrapperVehicles.push_back(wrapperVehicle);
@ -1300,6 +1307,20 @@ const PersistentManifold* CcdPhysicsEnvironment::GetManifold(int index) const
return GetDispatcher()->GetManifoldByIndexInternal(index);
}
Point2PointConstraint* CcdPhysicsEnvironment::getPoint2PointConstraint(int constraintId)
{
int nump2p = m_p2pConstraints.size();
int i;
for (i=0;i<nump2p;i++)
{
Point2PointConstraint* p2p = m_p2pConstraints[i];
if (p2p->GetUserConstraintId()==constraintId)
{
return p2p;
}
}
return 0;
}
#ifdef NEW_BULLET_VEHICLE_SUPPORT

@ -14,7 +14,7 @@ class Dispatcher;
//#include "BroadphaseInterface.h"
//switch on/off new vehicle support
#define NEW_BULLET_VEHICLE_SUPPORT 1
//#define NEW_BULLET_VEHICLE_SUPPORT 1
#include "ConstraintSolver/ContactSolverInfo.h"
@ -96,6 +96,8 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
}
#endif //NEW_BULLET_VEHICLE_SUPPORT
Point2PointConstraint* getPoint2PointConstraint(int constraintId);
virtual PHY_IPhysicsController* rayTest(PHY_IPhysicsController* ignoreClient, float fromX,float fromY,float fromZ, float toX,float toY,float toZ,
float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ);