Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <blender@erwincoumans.com>2006-11-13 00:05:10 +0300
committerErwin Coumans <blender@erwincoumans.com>2006-11-13 00:05:10 +0300
commit3a1b7ece402001f2f93669a7b36c32f5e7827bab (patch)
treea91e600407b0709922b7df3fa2a53f380cf7eb76 /extern/bullet2/src/BulletDynamics
parent22d97b2e346e3cb3fc38704a0460e2dd4d9a0abb (diff)
updating Bullet 2.x with latest changes. The integration + C-API will follow at some stage.
Diffstat (limited to 'extern/bullet2/src/BulletDynamics')
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp27
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp165
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp125
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h5
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp2
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp186
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h3
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h4
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp40
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h18
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp27
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h2
-rw-r--r--extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp61
-rw-r--r--extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h9
14 files changed, 476 insertions, 198 deletions
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp
index 429ad54d517..8d22689ec53 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp
@@ -164,7 +164,8 @@ float resolveSingleFriction(
float combinedFriction = cpd->m_friction;
btScalar limit = cpd->m_appliedImpulse * combinedFriction;
- //if (contactPoint.m_appliedImpulse>0.f)
+
+ if (cpd->m_appliedImpulse>0.f)
//friction
{
//apply friction in the 2 tangential directions
@@ -182,11 +183,12 @@ float resolveSingleFriction(
// calculate j that moves us to zero relative velocity
j1 = -vrel * cpd->m_jacDiagABInvTangent0;
- float total = cpd->m_accumulatedTangentImpulse0 + j1;
- GEN_set_min(total, limit);
- GEN_set_max(total, -limit);
- j1 = total - cpd->m_accumulatedTangentImpulse0;
- cpd->m_accumulatedTangentImpulse0 = total;
+ float oldTangentImpulse = cpd->m_accumulatedTangentImpulse0;
+ cpd->m_accumulatedTangentImpulse0 = oldTangentImpulse + j1;
+ GEN_set_min(cpd->m_accumulatedTangentImpulse0, limit);
+ GEN_set_max(cpd->m_accumulatedTangentImpulse0, -limit);
+ j1 = cpd->m_accumulatedTangentImpulse0 - oldTangentImpulse;
+
}
{
// 2nd tangent
@@ -195,11 +197,11 @@ float resolveSingleFriction(
// calculate j that moves us to zero relative velocity
j2 = -vrel * cpd->m_jacDiagABInvTangent1;
- float total = cpd->m_accumulatedTangentImpulse1 + j2;
- GEN_set_min(total, limit);
- GEN_set_max(total, -limit);
- j2 = total - cpd->m_accumulatedTangentImpulse1;
- cpd->m_accumulatedTangentImpulse1 = total;
+ float oldTangentImpulse = cpd->m_accumulatedTangentImpulse1;
+ cpd->m_accumulatedTangentImpulse1 = oldTangentImpulse + j2;
+ GEN_set_min(cpd->m_accumulatedTangentImpulse1, limit);
+ GEN_set_max(cpd->m_accumulatedTangentImpulse1, -limit);
+ j2 = cpd->m_accumulatedTangentImpulse1 - oldTangentImpulse;
}
#ifdef USE_INTERNAL_APPLY_IMPULSE
@@ -395,4 +397,5 @@ float resolveSingleFrictionEmpty(
const btContactSolverInfo& solverInfo)
{
return 0.f;
-}; \ No newline at end of file
+};
+
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp
index a8ab1bbad3a..b5783f824d4 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp
@@ -21,6 +21,7 @@ subject to the following restrictions:
static const btScalar kSign[] = { 1.0f, -1.0f, 1.0f };
static const int kAxisA[] = { 1, 0, 0 };
static const int kAxisB[] = { 2, 2, 1 };
+#define GENERIC_D6_DISABLE_WARMSTARTING 1
btGeneric6DofConstraint::btGeneric6DofConstraint()
{
@@ -47,7 +48,7 @@ btGeneric6DofConstraint::btGeneric6DofConstraint(btRigidBody& rbA, btRigidBody&
void btGeneric6DofConstraint::buildJacobian()
{
- btVector3 normal(0,0,0);
+ btVector3 localNormalInA(0,0,0);
const btVector3& pivotInA = m_frameInA.getOrigin();
const btVector3& pivotInB = m_frameInB.getOrigin();
@@ -64,7 +65,9 @@ void btGeneric6DofConstraint::buildJacobian()
{
if (isLimited(i))
{
- normal[i] = 1;
+ localNormalInA[i] = 1;
+ btVector3 normalWorld = m_rbA.getCenterOfMassTransform().getBasis() * localNormalInA;
+
// Create linear atom
new (&m_jacLinear[i]) btJacobianEntry(
@@ -72,19 +75,24 @@ void btGeneric6DofConstraint::buildJacobian()
m_rbB.getCenterOfMassTransform().getBasis().transpose(),
m_rbA.getCenterOfMassTransform()*pivotInA - m_rbA.getCenterOfMassPosition(),
m_rbB.getCenterOfMassTransform()*pivotInB - m_rbB.getCenterOfMassPosition(),
- normal,
+ normalWorld,
m_rbA.getInvInertiaDiagLocal(),
m_rbA.getInvMass(),
m_rbB.getInvInertiaDiagLocal(),
m_rbB.getInvMass());
+ //optionally disable warmstarting
+#ifdef GENERIC_D6_DISABLE_WARMSTARTING
+ m_accumulatedImpulse[i] = 0.f;
+#endif //GENERIC_D6_DISABLE_WARMSTARTING
+
// Apply accumulated impulse
- btVector3 impulse_vector = m_accumulatedImpulse[i] * normal;
+ btVector3 impulse_vector = m_accumulatedImpulse[i] * normalWorld;
m_rbA.applyImpulse( impulse_vector, rel_pos1);
m_rbB.applyImpulse(-impulse_vector, rel_pos2);
- normal[i] = 0;
+ localNormalInA[i] = 0;
}
}
@@ -106,6 +114,10 @@ void btGeneric6DofConstraint::buildJacobian()
m_rbA.getInvInertiaDiagLocal(),
m_rbB.getInvInertiaDiagLocal());
+#ifdef GENERIC_D6_DISABLE_WARMSTARTING
+ m_accumulatedImpulse[i + 3] = 0.f;
+#endif //GENERIC_D6_DISABLE_WARMSTARTING
+
// Apply accumulated impulse
btVector3 impulse_vector = m_accumulatedImpulse[i + 3] * axis;
@@ -115,6 +127,52 @@ void btGeneric6DofConstraint::buildJacobian()
}
}
+float getMatrixElem(const btMatrix3x3& mat,int index)
+{
+ int row = index%3;
+ int col = index / 3;
+ return mat[row][col];
+}
+
+///MatrixToEulerXYZ from http://www.geometrictools.com/LibFoundation/Mathematics/Wm4Matrix3.inl.html
+bool MatrixToEulerXYZ(const btMatrix3x3& mat,btVector3& xyz)
+{
+ // rot = cy*cz -cy*sz sy
+ // cz*sx*sy+cx*sz cx*cz-sx*sy*sz -cy*sx
+ // -cx*cz*sy+sx*sz cz*sx+cx*sy*sz cx*cy
+
+/// 0..8
+
+ if (getMatrixElem(mat,2) < 1.0f)
+ {
+ if (getMatrixElem(mat,2) > -1.0f)
+ {
+ xyz[0] = btAtan2(-getMatrixElem(mat,5),getMatrixElem(mat,8));
+ xyz[1] = btAsin(getMatrixElem(mat,2));
+ xyz[2] = btAtan2(-getMatrixElem(mat,1),getMatrixElem(mat,0));
+ return true;
+ }
+ else
+ {
+ // WARNING. Not unique. XA - ZA = -atan2(r10,r11)
+ xyz[0] = -btAtan2(getMatrixElem(mat,3),getMatrixElem(mat,4));
+ xyz[1] = -SIMD_HALF_PI;
+ xyz[2] = 0.0f;
+ return false;
+ }
+ }
+ else
+ {
+ // WARNING. Not unique. XAngle + ZAngle = atan2(r10,r11)
+ xyz[0] = btAtan2(getMatrixElem(mat,3),getMatrixElem(mat,4));
+ xyz[1] = SIMD_HALF_PI;
+ xyz[2] = 0.0;
+ return false;
+ }
+ return false;
+}
+
+
void btGeneric6DofConstraint::solveConstraint(btScalar timeStep)
{
btScalar tau = 0.1f;
@@ -126,7 +184,7 @@ void btGeneric6DofConstraint::solveConstraint(btScalar timeStep)
btVector3 rel_pos1 = pivotAInW - m_rbA.getCenterOfMassPosition();
btVector3 rel_pos2 = pivotBInW - m_rbB.getCenterOfMassPosition();
- btVector3 normal(0,0,0);
+ btVector3 localNormalInA(0,0,0);
int i;
// linear
@@ -137,8 +195,10 @@ void btGeneric6DofConstraint::solveConstraint(btScalar timeStep)
btVector3 angvelA = m_rbA.getCenterOfMassTransform().getBasis().transpose() * m_rbA.getAngularVelocity();
btVector3 angvelB = m_rbB.getCenterOfMassTransform().getBasis().transpose() * m_rbB.getAngularVelocity();
+ localNormalInA.setValue(0,0,0);
+ localNormalInA[i] = 1;
+ btVector3 normalWorld = m_rbA.getCenterOfMassTransform().getBasis() * localNormalInA;
- normal[i] = 1;
btScalar jacDiagABInv = 1.f / m_jacLinear[i].getDiagonal();
//velocity error (first order error)
@@ -146,19 +206,59 @@ void btGeneric6DofConstraint::solveConstraint(btScalar timeStep)
m_rbB.getLinearVelocity(),angvelB);
//positional error (zeroth order error)
- btScalar depth = -(pivotAInW - pivotBInW).dot(normal);
-
- btScalar impulse = (tau*depth/timeStep - damping*rel_vel) * jacDiagABInv;
- m_accumulatedImpulse[i] += impulse;
+ btScalar depth = -(pivotAInW - pivotBInW).dot(normalWorld);
+ btScalar lo = -1e30f;
+ btScalar hi = 1e30f;
+
+ //handle the limits
+ if (m_lowerLimit[i] < m_upperLimit[i])
+ {
+ {
+ if (depth > m_upperLimit[i])
+ {
+ depth -= m_upperLimit[i];
+ lo = 0.f;
+
+ } else
+ {
+ if (depth < m_lowerLimit[i])
+ {
+ depth -= m_lowerLimit[i];
+ hi = 0.f;
+ } else
+ {
+ continue;
+ }
+ }
+ }
+ }
- btVector3 impulse_vector = normal * impulse;
+ btScalar normalImpulse= (tau*depth/timeStep - damping*rel_vel) * jacDiagABInv;
+ float oldNormalImpulse = m_accumulatedImpulse[i];
+ float sum = oldNormalImpulse + normalImpulse;
+ m_accumulatedImpulse[i] = sum > hi ? 0.f : sum < lo ? 0.f : sum;
+ normalImpulse = m_accumulatedImpulse[i] - oldNormalImpulse;
+
+ btVector3 impulse_vector = normalWorld * normalImpulse;
m_rbA.applyImpulse( impulse_vector, rel_pos1);
m_rbB.applyImpulse(-impulse_vector, rel_pos2);
- normal[i] = 0;
+ localNormalInA[i] = 0;
}
}
+ btVector3 axis;
+ btScalar angle;
+ btTransform frameAWorld = m_rbA.getCenterOfMassTransform() * m_frameInA;
+ btTransform frameBWorld = m_rbB.getCenterOfMassTransform() * m_frameInB;
+
+ btTransformUtil::calculateDiffAxisAngle(frameAWorld,frameBWorld,axis,angle);
+ btQuaternion diff(axis,angle);
+ btMatrix3x3 diffMat (diff);
+ btVector3 xyz;
+ ///this is not perfect, we can first check which axis are limited, and choose a more appropriate order
+ MatrixToEulerXYZ(diffMat,xyz);
+
// angular
for (i=0;i<3;i++)
{
@@ -179,13 +279,46 @@ void btGeneric6DofConstraint::solveConstraint(btScalar timeStep)
btScalar rel_pos = kSign[i] * axisA.dot(axisB);
+ btScalar lo = -1e30f;
+ btScalar hi = 1e30f;
+
+ //handle the twist limit
+ if (m_lowerLimit[i+3] < m_upperLimit[i+3])
+ {
+ //clamp the values
+ btScalar loLimit = m_upperLimit[i+3] > -3.1415 ? m_lowerLimit[i+3] : -1e30f;
+ btScalar hiLimit = m_upperLimit[i+3] < 3.1415 ? m_upperLimit[i+3] : 1e30f;
+
+ float projAngle = -2.*xyz[i];
+
+ if (projAngle < loLimit)
+ {
+ hi = 0.f;
+ rel_pos = (loLimit - projAngle);
+ } else
+ {
+ if (projAngle > hiLimit)
+ {
+ lo = 0.f;
+ rel_pos = (hiLimit - projAngle);
+ } else
+ {
+ continue;
+ }
+ }
+ }
+
//impulse
- btScalar impulse = -(tau*rel_pos/timeStep + damping*rel_vel) * jacDiagABInv;
- m_accumulatedImpulse[i + 3] += impulse;
+
+ btScalar normalImpulse= -(tau*rel_pos/timeStep + damping*rel_vel) * jacDiagABInv;
+ float oldNormalImpulse = m_accumulatedImpulse[i+3];
+ float sum = oldNormalImpulse + normalImpulse;
+ m_accumulatedImpulse[i+3] = sum > hi ? 0.f : sum < lo ? 0.f : sum;
+ normalImpulse = m_accumulatedImpulse[i+3] - oldNormalImpulse;
// Dirk: Not needed - we could actually project onto Jacobian entry here (same as above)
btVector3 axis = kSign[i] * axisA.cross(axisB);
- btVector3 impulse_vector = axis * impulse;
+ btVector3 impulse_vector = axis * normalImpulse;
m_rbA.applyTorqueImpulse( impulse_vector);
m_rbB.applyTorqueImpulse(-impulse_vector);
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
index ac06f718c9e..568bcc40939 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
@@ -32,6 +32,27 @@ int totalCpd = 0;
int gTotalContactPoints = 0;
+struct btOrderIndex
+{
+ short int m_manifoldIndex;
+ short int m_pointIndex;
+};
+
+#define SEQUENTIAL_IMPULSE_MAX_SOLVER_POINTS 16384
+static btOrderIndex gOrder[SEQUENTIAL_IMPULSE_MAX_SOLVER_POINTS];
+static unsigned long btSeed2 = 0;
+unsigned long btRand2()
+{
+ btSeed2 = (1664525L*btSeed2 + 1013904223L) & 0xffffffff;
+ return btSeed2;
+}
+
+int btRandInt2 (int n)
+{
+ float a = float(n) / 4294967296.0f;
+ return (int) (float(btRand2()) * a);
+}
+
bool MyContactDestroyedCallback(void* userPersistentData)
{
assert (userPersistentData);
@@ -69,52 +90,62 @@ float btSequentialImpulseConstraintSolver::solveGroup(btPersistentManifold** man
btProfiler::beginBlock("solve");
#endif //USE_PROFILE
+ int totalPoints = 0;
+
{
int j;
for (j=0;j<numManifolds;j++)
{
- int k=j;
- prepareConstraints(manifoldPtr[k],info,debugDrawer);
- solve(manifoldPtr[k],info,0,debugDrawer);
+ prepareConstraints(manifoldPtr[j],info,debugDrawer);
}
}
-
-
- //should traverse the contacts random order...
- int i;
- for ( i = 0;i<numiter-1;i++)
+
{
int j;
for (j=0;j<numManifolds;j++)
{
- int k=j;
- if (i&1)
- k=numManifolds-j-1;
-
- solve(manifoldPtr[k],info,i,debugDrawer);
+ for (int p=0;p<manifoldPtr[j]->getNumContacts();p++)
+ {
+ gOrder[totalPoints].m_manifoldIndex = j;
+ gOrder[totalPoints].m_pointIndex = p;
+ totalPoints++;
+ }
}
-
}
-#ifdef USE_PROFILE
- btProfiler::endBlock("solve");
-
- btProfiler::beginBlock("solveFriction");
-#endif //USE_PROFILE
-
- //now solve the friction
- for (i = 0;i<numiter-1;i++)
+
+
+ //should traverse the contacts random order...
+ int iteration;
+ for ( iteration = 0;iteration<numiter-1;iteration++)
{
int j;
- for (j=0;j<numManifolds;j++)
+ if ((iteration & 7) == 0) {
+ for (j=0; j<totalPoints; ++j) {
+ btOrderIndex tmp = gOrder[j];
+ int swapi = btRandInt2(j+1);
+ gOrder[j] = gOrder[swapi];
+ gOrder[swapi] = tmp;
+ }
+ }
+
+ for (j=0;j<totalPoints;j++)
{
- int k = j;
- if (i&1)
- k=numManifolds-j-1;
- solveFriction(manifoldPtr[k],info,i,debugDrawer);
+ btPersistentManifold* manifold = manifoldPtr[gOrder[j].m_manifoldIndex];
+ solve( (btRigidBody*)manifold->getBody0(),
+ (btRigidBody*)manifold->getBody1()
+ ,manifold->getContactPoint(gOrder[j].m_pointIndex),info,iteration,debugDrawer);
+ }
+
+ for (j=0;j<totalPoints;j++)
+ {
+ btPersistentManifold* manifold = manifoldPtr[gOrder[j].m_manifoldIndex];
+ solveFriction((btRigidBody*)manifold->getBody0(),
+ (btRigidBody*)manifold->getBody1(),manifold->getContactPoint(gOrder[j].m_pointIndex),info,iteration,debugDrawer);
}
}
+
#ifdef USE_PROFILE
- btProfiler::endBlock("solveFriction");
+ btProfiler::endBlock("solve");
#endif //USE_PROFILE
return 0.f;
@@ -225,7 +256,7 @@ void btSequentialImpulseConstraintSolver::prepareConstraints(btPersistentManifol
btScalar penVel = -cpd->m_penetration/info.m_timeStep;
- if (cpd->m_restitution >= penVel)
+ if (cpd->m_restitution > penVel)
{
cpd->m_penetration = 0.f;
}
@@ -233,7 +264,7 @@ void btSequentialImpulseConstraintSolver::prepareConstraints(btPersistentManifol
float relaxation = info.m_damping;
- cpd->m_appliedImpulse *= relaxation;
+ cpd->m_appliedImpulse =0.f;//*= relaxation;
//for friction
cpd->m_prevAppliedImpulse = cpd->m_appliedImpulse;
@@ -260,8 +291,8 @@ void btSequentialImpulseConstraintSolver::prepareConstraints(btPersistentManifol
btVector3 totalImpulse =
#ifndef NO_FRICTION_WARMSTART
- cp.m_frictionWorldTangential0*cp.m_accumulatedTangentImpulse0+
- cp.m_frictionWorldTangential1*cp.m_accumulatedTangentImpulse1+
+ cpd->m_frictionWorldTangential0*cpd->m_accumulatedTangentImpulse0+
+ cpd->m_frictionWorldTangential1*cpd->m_accumulatedTangentImpulse1+
#endif //NO_FRICTION_WARMSTART
cp.m_normalWorldOnB*cpd->m_appliedImpulse;
@@ -304,29 +335,16 @@ void btSequentialImpulseConstraintSolver::prepareConstraints(btPersistentManifol
}
}
-float btSequentialImpulseConstraintSolver::solve(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
+float btSequentialImpulseConstraintSolver::solve(btRigidBody* body0,btRigidBody* body1, btManifoldPoint& cp, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
{
- btRigidBody* body0 = (btRigidBody*)manifoldPtr->getBody0();
- btRigidBody* body1 = (btRigidBody*)manifoldPtr->getBody1();
-
float maxImpulse = 0.f;
{
- const int numpoints = manifoldPtr->getNumContacts();
btVector3 color(0,1,0);
- for (int i=0;i<numpoints ;i++)
{
-
- int j=i;
- if (iter % 2)
- j = numpoints-1-i;
- else
- j=i;
-
- btManifoldPoint& cp = manifoldPtr->getContactPoint(j);
- if (cp.getDistance() <= 0.f)
+ if (cp.getDistance() <= 0.f)
{
if (iter == 0)
@@ -353,24 +371,15 @@ float btSequentialImpulseConstraintSolver::solve(btPersistentManifold* manifoldP
return maxImpulse;
}
-float btSequentialImpulseConstraintSolver::solveFriction(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
+float btSequentialImpulseConstraintSolver::solveFriction(btRigidBody* body0,btRigidBody* body1, btManifoldPoint& cp, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
{
- btRigidBody* body0 = (btRigidBody*)manifoldPtr->getBody0();
- btRigidBody* body1 = (btRigidBody*)manifoldPtr->getBody1();
{
- const int numpoints = manifoldPtr->getNumContacts();
btVector3 color(0,1,0);
- for (int i=0;i<numpoints ;i++)
{
-
- int j=i;
- //if (iter % 2)
- // j = numpoints-1-i;
-
- btManifoldPoint& cp = manifoldPtr->getContactPoint(j);
+
if (cp.getDistance() <= 0.f)
{
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
index e399a5cd734..8264f5071dd 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
@@ -29,8 +29,9 @@ class btIDebugDraw;
/// Applies impulses for combined restitution and penetration recovery and to simulate friction
class btSequentialImpulseConstraintSolver : public btConstraintSolver
{
- float solve(btPersistentManifold* manifold, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer);
- float solveFriction(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer);
+
+ float solve(btRigidBody* body0,btRigidBody* body1, btManifoldPoint& cp, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer);
+ float solveFriction(btRigidBody* body0,btRigidBody* body1, btManifoldPoint& cp, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer);
void prepareConstraints(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,btIDebugDraw* debugDrawer);
ContactSolverFunc m_contactDispatch[MAX_CONTACT_SOLVER_TYPES][MAX_CONTACT_SOLVER_TYPES];
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp
index ea7d5c8b903..cb3fa72d440 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp
@@ -17,7 +17,7 @@ subject to the following restrictions:
#include "btTypedConstraint.h"
#include "BulletDynamics/Dynamics/btRigidBody.h"
-static btRigidBody s_fixed(0, btTransform::getIdentity(),0);
+static btRigidBody s_fixed(0, 0,0);
btTypedConstraint::btTypedConstraint()
: m_userConstraintType(-1),
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
index 1bfc9b33348..125e933ad90 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
@@ -56,9 +56,10 @@ subject to the following restrictions:
#include <algorithm>
-btDiscreteDynamicsWorld::btDiscreteDynamicsWorld()
+
+btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btConstraintSolver* constraintSolver)
:btDynamicsWorld(),
-m_constraintSolver(new btSequentialImpulseConstraintSolver),
+m_constraintSolver(constraintSolver? constraintSolver: new btSequentialImpulseConstraintSolver),
m_debugDrawer(0),
m_gravity(0,-10,0),
m_localTime(1.f/60.f),
@@ -66,10 +67,10 @@ m_profileTimings(0)
{
m_islandManager = new btSimulationIslandManager();
m_ownsIslandManager = true;
- m_ownsConstraintSolver = true;
-
+ m_ownsConstraintSolver = (constraintSolver==0);
}
+
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
:btDynamicsWorld(dispatcher,pairCache),
m_constraintSolver(constraintSolver? constraintSolver: new btSequentialImpulseConstraintSolver),
@@ -103,7 +104,7 @@ void btDiscreteDynamicsWorld::saveKinematicState(float timeStep)
if (body)
{
btTransform predictedTrans;
- if (body->GetActivationState() != ISLAND_SLEEPING)
+ if (body->getActivationState() != ISLAND_SLEEPING)
{
if (body->isKinematicObject())
{
@@ -117,42 +118,82 @@ void btDiscreteDynamicsWorld::saveKinematicState(float timeStep)
void btDiscreteDynamicsWorld::synchronizeMotionStates()
{
- //todo: iterate over awake simulation islands!
- for (unsigned int i=0;i<m_collisionObjects.size();i++)
+ //debug vehicle wheels
+
+
{
- btCollisionObject* colObj = m_collisionObjects[i];
- if (getDebugDrawer() && getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_DrawWireframe)
+ //todo: iterate over awake simulation islands!
+ for (unsigned int i=0;i<m_collisionObjects.size();i++)
{
- btVector3 color(255.f,255.f,255.f);
- switch(colObj->GetActivationState())
+ btCollisionObject* colObj = m_collisionObjects[i];
+ if (getDebugDrawer() && getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_DrawWireframe)
{
- case ACTIVE_TAG:
- color = btVector3(255.f,255.f,255.f); break;
- case ISLAND_SLEEPING:
- color = btVector3(0.f,255.f,0.f);break;
- case WANTS_DEACTIVATION:
- color = btVector3(0.f,255.f,255.f);break;
- case DISABLE_DEACTIVATION:
- color = btVector3(255.f,0.f,0.f);break;
- case DISABLE_SIMULATION:
- color = btVector3(255.f,255.f,0.f);break;
- default:
+ btVector3 color(255.f,255.f,255.f);
+ switch(colObj->getActivationState())
{
- color = btVector3(255.f,0.f,0.f);
- }
- };
+ case ACTIVE_TAG:
+ color = btVector3(255.f,255.f,255.f); break;
+ case ISLAND_SLEEPING:
+ color = btVector3(0.f,255.f,0.f);break;
+ case WANTS_DEACTIVATION:
+ color = btVector3(0.f,255.f,255.f);break;
+ case DISABLE_DEACTIVATION:
+ color = btVector3(255.f,0.f,0.f);break;
+ case DISABLE_SIMULATION:
+ color = btVector3(255.f,255.f,0.f);break;
+ default:
+ {
+ color = btVector3(255.f,0.f,0.f);
+ }
+ };
- debugDrawObject(colObj->m_worldTransform,colObj->m_collisionShape,color);
+ debugDrawObject(colObj->getWorldTransform(),colObj->getCollisionShape(),color);
+ }
+ btRigidBody* body = btRigidBody::upcast(colObj);
+ if (body && body->getMotionState() && !body->isStaticOrKinematicObject())
+ {
+ if (body->getActivationState() != ISLAND_SLEEPING)
+ {
+ btTransform interpolatedTransform;
+ btTransformUtil::integrateTransform(body->getInterpolationWorldTransform(),
+ body->getInterpolationLinearVelocity(),body->getInterpolationAngularVelocity(),m_localTime,interpolatedTransform);
+ body->getMotionState()->setWorldTransform(interpolatedTransform);
+ }
+ }
}
- btRigidBody* body = btRigidBody::upcast(colObj);
- if (body && body->getMotionState() && !body->isStaticOrKinematicObject())
+ }
+
+ if (getDebugDrawer() && getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_DrawWireframe)
+ {
+ for (unsigned int i=0;i<this->m_vehicles.size();i++)
{
- if (body->GetActivationState() != ISLAND_SLEEPING)
+ for (int v=0;v<m_vehicles[i]->getNumWheels();v++)
{
- btTransform interpolatedTransform;
- btTransformUtil::integrateTransform(body->m_interpolationWorldTransform,
- body->m_interpolationLinearVelocity,body->m_interpolationAngularVelocity,m_localTime,interpolatedTransform);
- body->getMotionState()->setWorldTransform(interpolatedTransform);
+ btVector3 wheelColor(0,255,255);
+ if (m_vehicles[i]->getWheelInfo(v).m_raycastInfo.m_isInContact)
+ {
+ wheelColor.setValue(0,0,255);
+ } else
+ {
+ wheelColor.setValue(255,0,255);
+ }
+
+ //synchronize the wheels with the (interpolated) chassis worldtransform
+ m_vehicles[i]->updateWheelTransform(v,true);
+
+ btVector3 wheelPosWS = m_vehicles[i]->getWheelInfo(v).m_worldTransform.getOrigin();
+
+ btVector3 axle = btVector3(
+ m_vehicles[i]->getWheelInfo(v).m_worldTransform.getBasis()[0][m_vehicles[i]->getRightAxis()],
+ m_vehicles[i]->getWheelInfo(v).m_worldTransform.getBasis()[1][m_vehicles[i]->getRightAxis()],
+ m_vehicles[i]->getWheelInfo(v).m_worldTransform.getBasis()[2][m_vehicles[i]->getRightAxis()]);
+
+
+ //m_vehicles[i]->getWheelInfo(v).m_raycastInfo.m_wheelAxleWS
+ //debug wheels (cylinders)
+ m_debugDrawer->drawLine(wheelPosWS,wheelPosWS+axle,wheelColor);
+ m_debugDrawer->drawLine(wheelPosWS,m_vehicles[i]->getWheelInfo(v).m_raycastInfo.m_contactPointWS,wheelColor);
+
}
}
}
@@ -178,8 +219,15 @@ int btDiscreteDynamicsWorld::stepSimulation( float timeStep,int maxSubSteps, flo
//variable timestep
fixedTimeStep = timeStep;
m_localTime = timeStep;
- numSimulationSubSteps = 1;
- maxSubSteps = 1;
+ if (btFuzzyZero(timeStep))
+ {
+ numSimulationSubSteps = 0;
+ maxSubSteps = 0;
+ } else
+ {
+ numSimulationSubSteps = 1;
+ maxSubSteps = 1;
+ }
}
//process some debugging flags
@@ -187,7 +235,7 @@ int btDiscreteDynamicsWorld::stepSimulation( float timeStep,int maxSubSteps, flo
{
gDisableDeactivation = (getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_NoDeactivation) != 0;
}
- if (!btFuzzyZero(timeStep) && numSimulationSubSteps)
+ if (numSimulationSubSteps)
{
saveKinematicState(fixedTimeStep);
@@ -198,6 +246,7 @@ int btDiscreteDynamicsWorld::stepSimulation( float timeStep,int maxSubSteps, flo
for (int i=0;i<clampedSimulationSteps;i++)
{
internalSingleStepSimulation(fixedTimeStep);
+ synchronizeMotionStates();
}
}
@@ -226,20 +275,23 @@ void btDiscreteDynamicsWorld::internalSingleStepSimulation(float timeStep)
btContactSolverInfo infoGlobal;
infoGlobal.m_timeStep = timeStep;
+
+
///solve non-contact constraints
solveNoncontactConstraints(infoGlobal);
///solve contact constraints
solveContactConstraints(infoGlobal);
- ///update vehicle simulation
- updateVehicles(timeStep);
-
///CallbackTriggers();
///integrate transforms
integrateTransforms(timeStep);
-
+
+ ///update vehicle simulation
+ updateVehicles(timeStep);
+
+
updateActivationState( timeStep );
@@ -268,12 +320,19 @@ void btDiscreteDynamicsWorld::removeRigidBody(btRigidBody* body)
void btDiscreteDynamicsWorld::addRigidBody(btRigidBody* body)
{
- body->setGravity(m_gravity);
- bool isDynamic = !(body->isStaticObject() || body->isKinematicObject());
- short collisionFilterGroup = isDynamic? btBroadphaseProxy::DefaultFilter : btBroadphaseProxy::StaticFilter;
- short collisionFilterMask = isDynamic? btBroadphaseProxy::AllFilter : btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter;
+ if (!body->isStaticOrKinematicObject())
+ {
+ body->setGravity(m_gravity);
+ }
- addCollisionObject(body,collisionFilterGroup,collisionFilterMask);
+ if (body->getCollisionShape())
+ {
+ bool isDynamic = !(body->isStaticObject() || body->isKinematicObject());
+ short collisionFilterGroup = isDynamic? btBroadphaseProxy::DefaultFilter : btBroadphaseProxy::StaticFilter;
+ short collisionFilterMask = isDynamic? btBroadphaseProxy::AllFilter : btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter;
+
+ addCollisionObject(body,collisionFilterGroup,collisionFilterMask);
+ }
}
@@ -303,12 +362,12 @@ void btDiscreteDynamicsWorld::updateActivationState(float timeStep)
if (body->wantsSleeping())
{
- if (body->GetActivationState() == ACTIVE_TAG)
- body->SetActivationState( WANTS_DEACTIVATION );
+ if (body->getActivationState() == ACTIVE_TAG)
+ body->setActivationState( WANTS_DEACTIVATION );
} else
{
- if (body->GetActivationState() != DISABLE_DEACTIVATION)
- body->SetActivationState( ACTIVE_TAG );
+ if (body->getActivationState() != DISABLE_DEACTIVATION)
+ body->setActivationState( ACTIVE_TAG );
}
}
}
@@ -436,11 +495,11 @@ void btDiscreteDynamicsWorld::calculateSimulationIslands()
if (((colObj0) && ((colObj0)->mergesSimulationIslands())) &&
((colObj1) && ((colObj1)->mergesSimulationIslands())))
{
- if (colObj0->IsActive() || colObj1->IsActive())
+ if (colObj0->isActive() || colObj1->isActive())
{
- getSimulationIslandManager()->getUnionFind().unite((colObj0)->m_islandTag1,
- (colObj1)->m_islandTag1);
+ getSimulationIslandManager()->getUnionFind().unite((colObj0)->getIslandTag(),
+ (colObj1)->getIslandTag());
}
}
}
@@ -501,19 +560,19 @@ void btDiscreteDynamicsWorld::updateAabbs()
// if (body->IsActive() && (!body->IsStatic()))
{
btPoint3 minAabb,maxAabb;
- colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
+ colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_broadphasePairCache;
//moving objects should be moderately sized, probably something wrong if not
if ( colObj->isStaticObject() || ((maxAabb-minAabb).length2() < 1e12f))
{
- bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
+ bp->setAabb(body->getBroadphaseHandle(),minAabb,maxAabb);
} else
{
//something went wrong, investigate
//this assert is unwanted in 3D modelers (danger of loosing work)
assert(0);
- body->SetActivationState(DISABLE_SIMULATION);
+ body->setActivationState(DISABLE_SIMULATION);
static bool reportMe = true;
if (reportMe)
@@ -548,7 +607,7 @@ void btDiscreteDynamicsWorld::integrateTransforms(float timeStep)
btRigidBody* body = btRigidBody::upcast(colObj);
if (body)
{
- if (body->IsActive() && (!body->isStaticOrKinematicObject()))
+ if (body->isActive() && (!body->isStaticOrKinematicObject()))
{
body->predictIntegratedTransform(timeStep, predictedTrans);
body->proceedToTransform( predictedTrans);
@@ -571,11 +630,11 @@ void btDiscreteDynamicsWorld::predictUnconstraintMotion(float timeStep)
{
if (!body->isStaticOrKinematicObject())
{
- if (body->IsActive())
+ if (body->isActive())
{
body->applyForces( timeStep);
body->integrateVelocities( timeStep);
- body->predictIntegratedTransform(timeStep,body->m_interpolationWorldTransform);
+ body->predictIntegratedTransform(timeStep,body->getInterpolationWorldTransform());
}
}
}
@@ -768,3 +827,14 @@ void btDiscreteDynamicsWorld::debugDrawObject(const btTransform& worldTransform,
}
}
}
+
+void btDiscreteDynamicsWorld::setConstraintSolver(btConstraintSolver* solver)
+{
+ if (m_ownsConstraintSolver)
+ {
+ delete m_constraintSolver;
+ }
+ m_ownsConstraintSolver = false;
+ m_constraintSolver = solver;
+}
+
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
index 77e4ada645c..12939753442 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
@@ -86,7 +86,7 @@ public:
btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver=0);
///this btDiscreteDynamicsWorld will create and own dispatcher, pairCache and constraintSolver, and deletes it in the destructor.
- btDiscreteDynamicsWorld();
+ btDiscreteDynamicsWorld(btConstraintSolver* constraintSolver = 0);
virtual ~btDiscreteDynamicsWorld();
@@ -136,6 +136,7 @@ public:
void debugDrawObject(const btTransform& worldTransform, const btCollisionShape* shape, const btVector3& color);
+ virtual void setConstraintSolver(btConstraintSolver* solver);
};
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h
index fa916f65505..6023f29b4fb 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h
@@ -19,6 +19,8 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btCollisionWorld.h"
class btTypedConstraint;
class btRaycastVehicle;
+class btConstraintSolver;
+
///btDynamicsWorld is the baseclass for several dynamics implementation, basic, discrete, parallel, and continuous
class btDynamicsWorld : public btCollisionWorld
@@ -65,6 +67,8 @@ class btDynamicsWorld : public btCollisionWorld
virtual void removeRigidBody(btRigidBody* body) = 0;
+ virtual void setConstraintSolver(btConstraintSolver* solver) = 0;
+
};
#endif //BT_DYNAMICS_WORLD_H
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp
index a434f5e41dd..db05f37d8c8 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp
@@ -42,7 +42,13 @@ btRigidBody::btRigidBody(float mass, btMotionState* motionState, btCollisionShap
m_frictionSolverType(0)
{
- motionState->getWorldTransform(m_worldTransform);
+ if (motionState)
+ {
+ motionState->getWorldTransform(m_worldTransform);
+ } else
+ {
+ m_worldTransform = btTransform::getIdentity();
+ }
m_interpolationWorldTransform = m_worldTransform;
m_interpolationLinearVelocity.setValue(0,0,0);
@@ -64,7 +70,7 @@ btRigidBody::btRigidBody(float mass, btMotionState* motionState, btCollisionShap
}
-
+#ifdef OBSOLETE_MOTIONSTATE_LESS
btRigidBody::btRigidBody( float mass,const btTransform& worldTransform,btCollisionShape* collisionShape,const btVector3& localInertia,btScalar linearDamping,btScalar angularDamping,btScalar friction,btScalar restitution)
:
m_gravity(0.0f, 0.0f, 0.0f),
@@ -100,30 +106,34 @@ btRigidBody::btRigidBody( float mass,const btTransform& worldTransform,btCollisi
}
+#endif //OBSOLETE_MOTIONSTATE_LESS
+
+
#define EXPERIMENTAL_JITTER_REMOVAL 1
#ifdef EXPERIMENTAL_JITTER_REMOVAL
-//Bullet 2.20b has experimental code to reduce jitter just before objects fall asleep/deactivate
-//doesn't work very well yet (value 0 only reduces performance a bit, no difference in functionality)
-float gClippedAngvelThresholdSqr = 0.f;
-float gClippedLinearThresholdSqr = 0.f;
+//Bullet 2.20b has experimental damping code to reduce jitter just before objects fall asleep/deactivate
+//doesn't work very well yet (value 0 disabled this damping)
+//note there this influences deactivation thresholds!
+float gClippedAngvelThresholdSqr = 0.01f;
+float gClippedLinearThresholdSqr = 0.01f;
+float gJitterVelocityDampingFactor = 1.f;
#endif //EXPERIMENTAL_JITTER_REMOVAL
void btRigidBody::predictIntegratedTransform(btScalar timeStep,btTransform& predictedTransform)
{
#ifdef EXPERIMENTAL_JITTER_REMOVAL
- //clip to avoid jitter
- if (m_angularVelocity.length2() < gClippedAngvelThresholdSqr)
+ //if (wantsSleeping())
{
- m_angularVelocity.setValue(0,0,0);
- printf("clipped!\n");
+ //clip to avoid jitter
+ if ((m_angularVelocity.length2() < gClippedAngvelThresholdSqr) &&
+ (m_linearVelocity.length2() < gClippedLinearThresholdSqr))
+ {
+ m_angularVelocity *= gJitterVelocityDampingFactor;
+ m_linearVelocity *= gJitterVelocityDampingFactor;
+ }
}
- if (m_linearVelocity.length2() < gClippedLinearThresholdSqr)
- {
- m_linearVelocity.setValue(0,0,0);
- printf("clipped!\n");
- }
#endif //EXPERIMENTAL_JITTER_REMOVAL
btTransformUtil::integrateTransform(m_worldTransform,m_linearVelocity,m_angularVelocity,timeStep,predictedTransform);
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h
index fca3658cb31..c5fecdb87a6 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h
@@ -62,7 +62,11 @@ class btRigidBody : public btCollisionObject
public:
+#ifdef OBSOLETE_MOTIONSTATE_LESS
+ //not supported, please use btMotionState
btRigidBody(float mass, const btTransform& worldTransform, btCollisionShape* collisionShape, const btVector3& localInertia=btVector3(0,0,0),btScalar linearDamping=0.f,btScalar angularDamping=0.f,btScalar friction=0.5f,btScalar restitution=0.f);
+#endif //OBSOLETE_MOTIONSTATE_LESS
+
btRigidBody(float mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia=btVector3(0,0,0),btScalar linearDamping=0.f,btScalar angularDamping=0.f,btScalar friction=0.5f,btScalar restitution=0.f);
void proceedToTransform(const btTransform& newTrans);
@@ -71,11 +75,11 @@ public:
///but a rigidbody is derived from btCollisionObject, so we can safely perform an upcast
static const btRigidBody* upcast(const btCollisionObject* colObj)
{
- return (const btRigidBody*)colObj->m_internalOwner;
+ return (const btRigidBody*)colObj->getInternalOwner();
}
static btRigidBody* upcast(btCollisionObject* colObj)
{
- return (btRigidBody*)colObj->m_internalOwner;
+ return (btRigidBody*)colObj->getInternalOwner();
}
/// continuous collision detection needs prediction
@@ -247,7 +251,7 @@ public:
inline void updateDeactivation(float timeStep)
{
- if ( (GetActivationState() == ISLAND_SLEEPING) || (GetActivationState() == DISABLE_DEACTIVATION))
+ if ( (getActivationState() == ISLAND_SLEEPING) || (getActivationState() == DISABLE_DEACTIVATION))
return;
if ((getLinearVelocity().length2() < gLinearSleepingThreshold*gLinearSleepingThreshold) &&
@@ -257,7 +261,7 @@ public:
} else
{
m_deactivationTime=0.f;
- SetActivationState(0);
+ setActivationState(0);
}
}
@@ -265,14 +269,14 @@ public:
inline bool wantsSleeping()
{
- if (GetActivationState() == DISABLE_DEACTIVATION)
+ if (getActivationState() == DISABLE_DEACTIVATION)
return false;
//disable deactivation
if (gDisableDeactivation || (gDeactivationTime == 0.f))
return false;
- if ( (GetActivationState() == ISLAND_SLEEPING) || (GetActivationState() == WANTS_DEACTIVATION))
+ if ( (getActivationState() == ISLAND_SLEEPING) || (getActivationState() == WANTS_DEACTIVATION))
return true;
if (m_deactivationTime> gDeactivationTime)
@@ -309,6 +313,8 @@ public:
void setMotionState(btMotionState* motionState)
{
m_optionalMotionState = motionState;
+ if (m_optionalMotionState)
+ motionState->getWorldTransform(m_worldTransform);
}
//for experimental overriding of friction/contact solver func
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp b/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp
index 53a088de750..dabf291669d 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp
@@ -114,12 +114,12 @@ void btSimpleDynamicsWorld::updateAabbs()
btRigidBody* body = btRigidBody::upcast(colObj);
if (body)
{
- if (body->IsActive() && (!body->isStaticObject()))
+ if (body->isActive() && (!body->isStaticObject()))
{
btPoint3 minAabb,maxAabb;
- colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
+ colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
btBroadphaseInterface* bp = getBroadphase();
- bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
+ bp->setAabb(body->getBroadphaseHandle(),minAabb,maxAabb);
}
}
}
@@ -134,7 +134,7 @@ void btSimpleDynamicsWorld::integrateTransforms(float timeStep)
btRigidBody* body = btRigidBody::upcast(colObj);
if (body)
{
- if (body->IsActive() && (!body->isStaticObject()))
+ if (body->isActive() && (!body->isStaticObject()))
{
body->predictIntegratedTransform(timeStep, predictedTrans);
body->proceedToTransform( predictedTrans);
@@ -155,11 +155,11 @@ void btSimpleDynamicsWorld::predictUnconstraintMotion(float timeStep)
{
if (!body->isStaticObject())
{
- if (body->IsActive())
+ if (body->isActive())
{
body->applyForces( timeStep);
body->integrateVelocities( timeStep);
- body->predictIntegratedTransform(timeStep,body->m_interpolationWorldTransform);
+ body->predictIntegratedTransform(timeStep,body->getInterpolationWorldTransform());
}
}
}
@@ -176,11 +176,22 @@ void btSimpleDynamicsWorld::synchronizeMotionStates()
btRigidBody* body = btRigidBody::upcast(colObj);
if (body && body->getMotionState())
{
- if (body->GetActivationState() != ISLAND_SLEEPING)
+ if (body->getActivationState() != ISLAND_SLEEPING)
{
- body->getMotionState()->setWorldTransform(body->m_worldTransform);
+ body->getMotionState()->setWorldTransform(body->getWorldTransform());
}
}
}
}
+
+
+void btSimpleDynamicsWorld::setConstraintSolver(btConstraintSolver* solver)
+{
+ if (m_ownsConstraintSolver)
+ {
+ delete m_constraintSolver;
+ }
+ m_ownsConstraintSolver = false;
+ m_constraintSolver = solver;
+}
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h b/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h
index a65b56c4f57..f74e2460732 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h
@@ -77,6 +77,8 @@ public:
void synchronizeMotionStates();
+ virtual void setConstraintSolver(btConstraintSolver* solver);
+
};
#endif //BT_SIMPLE_DYNAMICS_WORLD_H
diff --git a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp
index 7a2043e2b38..700bdb866cd 100644
--- a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp
+++ b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp
@@ -11,6 +11,7 @@
#include "LinearMath/btVector3.h"
#include "btRaycastVehicle.h"
+
#include "BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h"
#include "BulletDynamics/ConstraintSolver/btJacobianEntry.h"
#include "LinearMath/btQuaternion.h"
@@ -23,7 +24,7 @@
-static btRigidBody s_fixedObject( 0,btTransform(btQuaternion(0,0,0,1)),0);
+static btRigidBody s_fixedObject( 0,0,0);
btRaycastVehicle::btRaycastVehicle(const btVehicleTuning& tuning,btRigidBody* chassis, btVehicleRaycaster* raycaster )
:m_vehicleRaycaster(raycaster),
@@ -75,8 +76,8 @@ btWheelInfo& btRaycastVehicle::addWheel( const btVector3& connectionPointCS, con
btWheelInfo& wheel = m_wheelInfo[getNumWheels()-1];
- updateWheelTransformsWS( wheel );
- updateWheelTransform(getNumWheels()-1);
+ updateWheelTransformsWS( wheel , false );
+ updateWheelTransform(getNumWheels()-1,false);
return wheel;
}
@@ -91,15 +92,18 @@ const btTransform& btRaycastVehicle::getWheelTransformWS( int wheelIndex ) const
}
-void btRaycastVehicle::updateWheelTransform( int wheelIndex )
+void btRaycastVehicle::updateWheelTransform( int wheelIndex , bool interpolatedTransform)
{
btWheelInfo& wheel = m_wheelInfo[ wheelIndex ];
- updateWheelTransformsWS(wheel);
+ updateWheelTransformsWS(wheel,interpolatedTransform);
btVector3 up = -wheel.m_raycastInfo.m_wheelDirectionWS;
const btVector3& right = wheel.m_raycastInfo.m_wheelAxleWS;
btVector3 fwd = up.cross(right);
fwd = fwd.normalize();
+// up = right.cross(fwd);
+// up.normalize();
+
//rotate around steering over de wheelAxleWS
float steering = wheel.m_steering;
@@ -138,16 +142,16 @@ void btRaycastVehicle::resetSuspension()
}
}
-void btRaycastVehicle::updateWheelTransformsWS(btWheelInfo& wheel )
+void btRaycastVehicle::updateWheelTransformsWS(btWheelInfo& wheel , bool interpolatedTransform)
{
wheel.m_raycastInfo.m_isInContact = false;
- btTransform chassisTrans;
- if (getRigidBody()->getMotionState())
+ btTransform chassisTrans = getChassisWorldTransform();
+ if (interpolatedTransform && (getRigidBody()->getMotionState()))
+ {
getRigidBody()->getMotionState()->getWorldTransform(chassisTrans);
- else
- chassisTrans = getRigidBody()->getCenterOfMassTransform();
-
+ }
+
wheel.m_raycastInfo.m_hardPointWS = chassisTrans( wheel.m_chassisConnectionPointCS );
wheel.m_raycastInfo.m_wheelDirectionWS = chassisTrans.getBasis() * wheel.m_wheelDirectionCS ;
wheel.m_raycastInfo.m_wheelAxleWS = chassisTrans.getBasis() * wheel.m_wheelAxleCS;
@@ -155,7 +159,7 @@ void btRaycastVehicle::updateWheelTransformsWS(btWheelInfo& wheel )
btScalar btRaycastVehicle::rayCast(btWheelInfo& wheel)
{
- updateWheelTransformsWS( wheel );
+ updateWheelTransformsWS( wheel,false);
btScalar depth = -1;
@@ -239,12 +243,35 @@ btScalar btRaycastVehicle::rayCast(btWheelInfo& wheel)
}
+const btTransform& btRaycastVehicle::getChassisWorldTransform() const
+{
+ /*if (getRigidBody()->getMotionState())
+ {
+ btTransform chassisWorldTrans;
+ getRigidBody()->getMotionState()->getWorldTransform(chassisWorldTrans);
+ return chassisWorldTrans;
+ }
+ */
+
+
+ return getRigidBody()->getCenterOfMassTransform();
+}
+
+
void btRaycastVehicle::updateVehicle( btScalar step )
{
+ {
+ for (int i=0;i<getNumWheels();i++)
+ {
+ updateWheelTransform(i,false);
+ }
+ }
+
m_currentVehicleSpeedKmHour = 3.6f * getRigidBody()->getLinearVelocity().length();
- const btTransform& chassisTrans = getRigidBody()->getCenterOfMassTransform();
+ const btTransform& chassisTrans = getChassisWorldTransform();
+
btVector3 forwardW (
chassisTrans.getBasis()[0][m_indexForwardAxis],
chassisTrans.getBasis()[1][m_indexForwardAxis],
@@ -304,10 +331,12 @@ void btRaycastVehicle::updateVehicle( btScalar step )
if (wheel.m_raycastInfo.m_isInContact)
{
+ const btTransform& chassisWorldTransform = getChassisWorldTransform();
+
btVector3 fwd (
- getRigidBody()->getCenterOfMassTransform().getBasis()[0][m_indexForwardAxis],
- getRigidBody()->getCenterOfMassTransform().getBasis()[1][m_indexForwardAxis],
- getRigidBody()->getCenterOfMassTransform().getBasis()[2][m_indexForwardAxis]);
+ chassisWorldTransform.getBasis()[0][m_indexForwardAxis],
+ chassisWorldTransform.getBasis()[1][m_indexForwardAxis],
+ chassisWorldTransform.getBasis()[2][m_indexForwardAxis]);
btScalar proj = fwd.dot(wheel.m_raycastInfo.m_contactNormalWS);
fwd -= wheel.m_raycastInfo.m_contactNormalWS * proj;
diff --git a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h
index a7534c67555..b928248cc2d 100644
--- a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h
+++ b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h
@@ -68,9 +68,8 @@ public:
virtual ~btRaycastVehicle() ;
-
-
-
+ const btTransform& getChassisWorldTransform() const;
+
btScalar rayCast(btWheelInfo& wheel);
virtual void updateVehicle(btScalar step);
@@ -86,7 +85,7 @@ public:
const btTransform& getWheelTransformWS( int wheelIndex ) const;
- void updateWheelTransform( int wheelIndex );
+ void updateWheelTransform( int wheelIndex, bool interpolatedTransform = true );
void setRaycastWheelInfo( int wheelIndex , bool isInContact, const btVector3& hitPoint, const btVector3& hitNormal,btScalar depth);
@@ -103,7 +102,7 @@ public:
btWheelInfo& getWheelInfo(int index);
- void updateWheelTransformsWS(btWheelInfo& wheel );
+ void updateWheelTransformsWS(btWheelInfo& wheel , bool interpolatedTransform = true);
void setBrake(float brake,int wheelIndex);