Refactoring: another huge number of changes, renamed methods to start with lower-case.
This commit is contained in:
@@ -31,7 +31,7 @@ public:
|
||||
|
||||
virtual ~btConstraintSolver() {}
|
||||
|
||||
virtual float SolveGroup(btPersistentManifold** manifold,int numManifolds,const btContactSolverInfo& info,class btIDebugDraw* debugDrawer = 0) = 0;
|
||||
virtual float solveGroup(btPersistentManifold** manifold,int numManifolds,const btContactSolverInfo& info,class btIDebugDraw* debugDrawer = 0) = 0;
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -100,8 +100,8 @@ float resolveSingleCollision(
|
||||
)
|
||||
{
|
||||
|
||||
const btVector3& pos1 = contactPoint.GetPositionWorldOnA();
|
||||
const btVector3& pos2 = contactPoint.GetPositionWorldOnB();
|
||||
const btVector3& pos1 = contactPoint.getPositionWorldOnA();
|
||||
const btVector3& pos2 = contactPoint.getPositionWorldOnB();
|
||||
|
||||
|
||||
// printf("distance=%f\n",distance);
|
||||
@@ -136,7 +136,7 @@ float resolveSingleCollision(
|
||||
btConstraintPersistentData* cpd = (btConstraintPersistentData*) contactPoint.m_userPersistentData;
|
||||
assert(cpd);
|
||||
|
||||
btScalar distance = cpd->m_penetration;//contactPoint.GetDistance();
|
||||
btScalar distance = cpd->m_penetration;//contactPoint.getDistance();
|
||||
|
||||
|
||||
//distance = 0.f;
|
||||
@@ -174,8 +174,8 @@ float resolveSingleFriction(
|
||||
)
|
||||
{
|
||||
|
||||
const btVector3& pos1 = contactPoint.GetPositionWorldOnA();
|
||||
const btVector3& pos2 = contactPoint.GetPositionWorldOnB();
|
||||
const btVector3& pos1 = contactPoint.getPositionWorldOnA();
|
||||
const btVector3& pos2 = contactPoint.getPositionWorldOnB();
|
||||
|
||||
btVector3 rel_pos1 = pos1 - body1.getCenterOfMassPosition();
|
||||
btVector3 rel_pos2 = pos2 - body2.getCenterOfMassPosition();
|
||||
|
||||
@@ -46,7 +46,7 @@ btGeneric6DofConstraint::btGeneric6DofConstraint(btRigidBody& rbA, btRigidBody&
|
||||
}
|
||||
|
||||
|
||||
void btGeneric6DofConstraint::BuildJacobian()
|
||||
void btGeneric6DofConstraint::buildJacobian()
|
||||
{
|
||||
btVector3 normal(0,0,0);
|
||||
|
||||
@@ -116,7 +116,7 @@ void btGeneric6DofConstraint::BuildJacobian()
|
||||
}
|
||||
}
|
||||
|
||||
void btGeneric6DofConstraint::SolveConstraint(btScalar timeStep)
|
||||
void btGeneric6DofConstraint::solveConstraint(btScalar timeStep)
|
||||
{
|
||||
btScalar tau = 0.1f;
|
||||
btScalar damping = 1.0f;
|
||||
@@ -194,12 +194,12 @@ void btGeneric6DofConstraint::SolveConstraint(btScalar timeStep)
|
||||
}
|
||||
}
|
||||
|
||||
void btGeneric6DofConstraint::UpdateRHS(btScalar timeStep)
|
||||
void btGeneric6DofConstraint::updateRHS(btScalar timeStep)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
btScalar btGeneric6DofConstraint::ComputeAngle(int axis) const
|
||||
btScalar btGeneric6DofConstraint::computeAngle(int axis) const
|
||||
{
|
||||
btScalar angle;
|
||||
|
||||
|
||||
@@ -47,13 +47,13 @@ public:
|
||||
|
||||
btGeneric6DofConstraint();
|
||||
|
||||
virtual void BuildJacobian();
|
||||
virtual void buildJacobian();
|
||||
|
||||
virtual void SolveConstraint(btScalar timeStep);
|
||||
virtual void solveConstraint(btScalar timeStep);
|
||||
|
||||
void UpdateRHS(btScalar timeStep);
|
||||
void updateRHS(btScalar timeStep);
|
||||
|
||||
btScalar ComputeAngle(int axis) const;
|
||||
btScalar computeAngle(int axis) const;
|
||||
|
||||
void setLinearLowerLimit(const btVector3& linearLower)
|
||||
{
|
||||
@@ -99,11 +99,11 @@ public:
|
||||
return (m_upperLimit[limitIndex] >= m_lowerLimit[limitIndex]);
|
||||
}
|
||||
|
||||
const btRigidBody& GetRigidBodyA() const
|
||||
const btRigidBody& getRigidBodyA() const
|
||||
{
|
||||
return m_rbA;
|
||||
}
|
||||
const btRigidBody& GetRigidBodyB() const
|
||||
const btRigidBody& getRigidBodyB() const
|
||||
{
|
||||
return m_rbB;
|
||||
}
|
||||
|
||||
@@ -45,7 +45,7 @@ m_angularOnly(false)
|
||||
|
||||
}
|
||||
|
||||
void btHingeConstraint::BuildJacobian()
|
||||
void btHingeConstraint::buildJacobian()
|
||||
{
|
||||
m_appliedImpulse = 0.f;
|
||||
|
||||
@@ -74,7 +74,7 @@ void btHingeConstraint::BuildJacobian()
|
||||
//these two jointAxis require equal angular velocities for both bodies
|
||||
|
||||
//this is unused for now, it's a todo
|
||||
btVector3 axisWorldA = GetRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA;
|
||||
btVector3 axisWorldA = getRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA;
|
||||
btVector3 jointAxis0;
|
||||
btVector3 jointAxis1;
|
||||
btPlaneSpace1(axisWorldA,jointAxis0,jointAxis1);
|
||||
@@ -94,7 +94,7 @@ void btHingeConstraint::BuildJacobian()
|
||||
|
||||
}
|
||||
|
||||
void btHingeConstraint::SolveConstraint(btScalar timeStep)
|
||||
void btHingeConstraint::solveConstraint(btScalar timeStep)
|
||||
{
|
||||
//#define NEW_IMPLEMENTATION
|
||||
|
||||
@@ -150,8 +150,8 @@ void btHingeConstraint::SolveConstraint(btScalar timeStep)
|
||||
///solve angular part
|
||||
|
||||
// get axes in world space
|
||||
btVector3 axisA = GetRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA;
|
||||
btVector3 axisB = GetRigidBodyB().getCenterOfMassTransform().getBasis() * m_axisInB;
|
||||
btVector3 axisA = getRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA;
|
||||
btVector3 axisB = getRigidBodyB().getCenterOfMassTransform().getBasis() * m_axisInB;
|
||||
|
||||
// constraint axes in world space
|
||||
btVector3 jointAxis0;
|
||||
@@ -230,11 +230,11 @@ void btHingeConstraint::SolveConstraint(btScalar timeStep)
|
||||
///solve angular part
|
||||
|
||||
// get axes in world space
|
||||
btVector3 axisA = GetRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA;
|
||||
btVector3 axisB = GetRigidBodyB().getCenterOfMassTransform().getBasis() * m_axisInB;
|
||||
btVector3 axisA = getRigidBodyA().getCenterOfMassTransform().getBasis() * m_axisInA;
|
||||
btVector3 axisB = getRigidBodyB().getCenterOfMassTransform().getBasis() * m_axisInB;
|
||||
|
||||
const btVector3& angVelA = GetRigidBodyA().getAngularVelocity();
|
||||
const btVector3& angVelB = GetRigidBodyB().getAngularVelocity();
|
||||
const btVector3& angVelA = getRigidBodyA().getAngularVelocity();
|
||||
const btVector3& angVelB = getRigidBodyB().getAngularVelocity();
|
||||
btVector3 angA = angVelA - axisA * axisA.dot(angVelA);
|
||||
btVector3 angB = angVelB - axisB * axisB.dot(angVelB);
|
||||
btVector3 velrel = angA-angB;
|
||||
@@ -245,8 +245,8 @@ void btHingeConstraint::SolveConstraint(btScalar timeStep)
|
||||
if (len > 0.00001f)
|
||||
{
|
||||
btVector3 normal = velrel.normalized();
|
||||
float denom = GetRigidBodyA().ComputeAngularImpulseDenominator(normal) +
|
||||
GetRigidBodyB().ComputeAngularImpulseDenominator(normal);
|
||||
float denom = getRigidBodyA().computeAngularImpulseDenominator(normal) +
|
||||
getRigidBodyB().computeAngularImpulseDenominator(normal);
|
||||
// scale for mass and relaxation
|
||||
velrel *= (1.f/denom) * 0.9;
|
||||
}
|
||||
@@ -257,8 +257,8 @@ void btHingeConstraint::SolveConstraint(btScalar timeStep)
|
||||
if (len2>0.00001f)
|
||||
{
|
||||
btVector3 normal2 = angularError.normalized();
|
||||
float denom2 = GetRigidBodyA().ComputeAngularImpulseDenominator(normal2) +
|
||||
GetRigidBodyB().ComputeAngularImpulseDenominator(normal2);
|
||||
float denom2 = getRigidBodyA().computeAngularImpulseDenominator(normal2) +
|
||||
getRigidBodyB().computeAngularImpulseDenominator(normal2);
|
||||
angularError *= (1.f/denom2) * relaxation;
|
||||
}
|
||||
|
||||
@@ -269,7 +269,7 @@ void btHingeConstraint::SolveConstraint(btScalar timeStep)
|
||||
|
||||
}
|
||||
|
||||
void btHingeConstraint::UpdateRHS(btScalar timeStep)
|
||||
void btHingeConstraint::updateRHS(btScalar timeStep)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
@@ -46,17 +46,17 @@ public:
|
||||
|
||||
btHingeConstraint();
|
||||
|
||||
virtual void BuildJacobian();
|
||||
virtual void buildJacobian();
|
||||
|
||||
virtual void SolveConstraint(btScalar timeStep);
|
||||
virtual void solveConstraint(btScalar timeStep);
|
||||
|
||||
void UpdateRHS(btScalar timeStep);
|
||||
void updateRHS(btScalar timeStep);
|
||||
|
||||
const btRigidBody& GetRigidBodyA() const
|
||||
const btRigidBody& getRigidBodyA() const
|
||||
{
|
||||
return m_rbA;
|
||||
}
|
||||
const btRigidBody& GetRigidBodyB() const
|
||||
const btRigidBody& getRigidBodyB() const
|
||||
{
|
||||
return m_rbB;
|
||||
}
|
||||
|
||||
@@ -38,7 +38,7 @@ btPoint2PointConstraint::btPoint2PointConstraint(btRigidBody& rbA,const btVector
|
||||
|
||||
}
|
||||
|
||||
void btPoint2PointConstraint::BuildJacobian()
|
||||
void btPoint2PointConstraint::buildJacobian()
|
||||
{
|
||||
m_appliedImpulse = 0.f;
|
||||
|
||||
@@ -62,7 +62,7 @@ void btPoint2PointConstraint::BuildJacobian()
|
||||
|
||||
}
|
||||
|
||||
void btPoint2PointConstraint::SolveConstraint(btScalar timeStep)
|
||||
void btPoint2PointConstraint::solveConstraint(btScalar timeStep)
|
||||
{
|
||||
btVector3 pivotAInW = m_rbA.getCenterOfMassTransform()*m_pivotInA;
|
||||
btVector3 pivotBInW = m_rbB.getCenterOfMassTransform()*m_pivotInB;
|
||||
@@ -109,7 +109,7 @@ void btPoint2PointConstraint::SolveConstraint(btScalar timeStep)
|
||||
}
|
||||
}
|
||||
|
||||
void btPoint2PointConstraint::UpdateRHS(btScalar timeStep)
|
||||
void btPoint2PointConstraint::updateRHS(btScalar timeStep)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
@@ -54,19 +54,19 @@ public:
|
||||
|
||||
btPoint2PointConstraint();
|
||||
|
||||
virtual void BuildJacobian();
|
||||
virtual void buildJacobian();
|
||||
|
||||
|
||||
virtual void SolveConstraint(btScalar timeStep);
|
||||
virtual void solveConstraint(btScalar timeStep);
|
||||
|
||||
void UpdateRHS(btScalar timeStep);
|
||||
void updateRHS(btScalar timeStep);
|
||||
|
||||
void SetPivotA(const btVector3& pivotA)
|
||||
void setPivotA(const btVector3& pivotA)
|
||||
{
|
||||
m_pivotInA = pivotA;
|
||||
}
|
||||
|
||||
void SetPivotB(const btVector3& pivotB)
|
||||
void setPivotB(const btVector3& pivotB)
|
||||
{
|
||||
m_pivotInB = pivotB;
|
||||
}
|
||||
|
||||
@@ -59,14 +59,14 @@ btSequentialImpulseConstraintSolver::btSequentialImpulseConstraintSolver()
|
||||
}
|
||||
|
||||
/// btSequentialImpulseConstraintSolver Sequentially applies impulses
|
||||
float btSequentialImpulseConstraintSolver::SolveGroup(btPersistentManifold** manifoldPtr, int numManifolds,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer)
|
||||
float btSequentialImpulseConstraintSolver::solveGroup(btPersistentManifold** manifoldPtr, int numManifolds,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer)
|
||||
{
|
||||
|
||||
btContactSolverInfo info = infoGlobal;
|
||||
|
||||
int numiter = infoGlobal.m_numIterations;
|
||||
#ifdef USE_PROFILE
|
||||
btProfiler::beginBlock("Solve");
|
||||
btProfiler::beginBlock("solve");
|
||||
#endif //USE_PROFILE
|
||||
|
||||
{
|
||||
@@ -76,8 +76,8 @@ float btSequentialImpulseConstraintSolver::SolveGroup(btPersistentManifold** man
|
||||
int k=j;
|
||||
//interleaving the preparation with solving impacts the behaviour a lot, todo: find out why
|
||||
|
||||
PrepareConstraints(manifoldPtr[k],info,debugDrawer);
|
||||
Solve(manifoldPtr[k],info,0,debugDrawer);
|
||||
prepareConstraints(manifoldPtr[k],info,debugDrawer);
|
||||
solve(manifoldPtr[k],info,0,debugDrawer);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -93,14 +93,14 @@ float btSequentialImpulseConstraintSolver::SolveGroup(btPersistentManifold** man
|
||||
if (i&1)
|
||||
k=numManifolds-j-1;
|
||||
|
||||
Solve(manifoldPtr[k],info,i,debugDrawer);
|
||||
solve(manifoldPtr[k],info,i,debugDrawer);
|
||||
}
|
||||
|
||||
}
|
||||
#ifdef USE_PROFILE
|
||||
btProfiler::endBlock("Solve");
|
||||
btProfiler::endBlock("solve");
|
||||
|
||||
btProfiler::beginBlock("SolveFriction");
|
||||
btProfiler::beginBlock("solveFriction");
|
||||
#endif //USE_PROFILE
|
||||
|
||||
//now solve the friction
|
||||
@@ -112,11 +112,11 @@ float btSequentialImpulseConstraintSolver::SolveGroup(btPersistentManifold** man
|
||||
int k = j;
|
||||
if (i&1)
|
||||
k=numManifolds-j-1;
|
||||
SolveFriction(manifoldPtr[k],info,i,debugDrawer);
|
||||
solveFriction(manifoldPtr[k],info,i,debugDrawer);
|
||||
}
|
||||
}
|
||||
#ifdef USE_PROFILE
|
||||
btProfiler::endBlock("SolveFriction");
|
||||
btProfiler::endBlock("solveFriction");
|
||||
#endif //USE_PROFILE
|
||||
|
||||
return 0.f;
|
||||
@@ -131,29 +131,29 @@ btScalar restitutionCurve(btScalar rel_vel, btScalar restitution)
|
||||
}
|
||||
|
||||
|
||||
void btSequentialImpulseConstraintSolver::PrepareConstraints(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,btIDebugDraw* debugDrawer)
|
||||
void btSequentialImpulseConstraintSolver::prepareConstraints(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,btIDebugDraw* debugDrawer)
|
||||
{
|
||||
|
||||
btRigidBody* body0 = (btRigidBody*)manifoldPtr->GetBody0();
|
||||
btRigidBody* body1 = (btRigidBody*)manifoldPtr->GetBody1();
|
||||
btRigidBody* body0 = (btRigidBody*)manifoldPtr->getBody0();
|
||||
btRigidBody* body1 = (btRigidBody*)manifoldPtr->getBody1();
|
||||
|
||||
|
||||
//only necessary to refresh the manifold once (first iteration). The integration is done outside the loop
|
||||
{
|
||||
manifoldPtr->RefreshContactPoints(body0->getCenterOfMassTransform(),body1->getCenterOfMassTransform());
|
||||
manifoldPtr->refreshContactPoints(body0->getCenterOfMassTransform(),body1->getCenterOfMassTransform());
|
||||
|
||||
int numpoints = manifoldPtr->GetNumContacts();
|
||||
int numpoints = manifoldPtr->getNumContacts();
|
||||
|
||||
gTotalContactPoints += numpoints;
|
||||
|
||||
btVector3 color(0,1,0);
|
||||
for (int i=0;i<numpoints ;i++)
|
||||
{
|
||||
btManifoldPoint& cp = manifoldPtr->GetContactPoint(i);
|
||||
if (cp.GetDistance() <= 0.f)
|
||||
btManifoldPoint& cp = manifoldPtr->getContactPoint(i);
|
||||
if (cp.getDistance() <= 0.f)
|
||||
{
|
||||
const btVector3& pos1 = cp.GetPositionWorldOnA();
|
||||
const btVector3& pos2 = cp.GetPositionWorldOnB();
|
||||
const btVector3& pos1 = cp.getPositionWorldOnA();
|
||||
const btVector3& pos2 = cp.getPositionWorldOnB();
|
||||
|
||||
btVector3 rel_pos1 = pos1 - body0->getCenterOfMassPosition();
|
||||
btVector3 rel_pos2 = pos2 - body1->getCenterOfMassPosition();
|
||||
@@ -173,15 +173,15 @@ void btSequentialImpulseConstraintSolver::PrepareConstraints(btPersistentManifol
|
||||
{
|
||||
//might be invalid
|
||||
cpd->m_persistentLifeTime++;
|
||||
if (cpd->m_persistentLifeTime != cp.GetLifeTime())
|
||||
if (cpd->m_persistentLifeTime != cp.getLifeTime())
|
||||
{
|
||||
//printf("Invalid: cpd->m_persistentLifeTime = %i cp.GetLifeTime() = %i\n",cpd->m_persistentLifeTime,cp.GetLifeTime());
|
||||
//printf("Invalid: cpd->m_persistentLifeTime = %i cp.getLifeTime() = %i\n",cpd->m_persistentLifeTime,cp.getLifeTime());
|
||||
new (cpd) btConstraintPersistentData;
|
||||
cpd->m_persistentLifeTime = cp.GetLifeTime();
|
||||
cpd->m_persistentLifeTime = cp.getLifeTime();
|
||||
|
||||
} else
|
||||
{
|
||||
//printf("Persistent: cpd->m_persistentLifeTime = %i cp.GetLifeTime() = %i\n",cpd->m_persistentLifeTime,cp.GetLifeTime());
|
||||
//printf("Persistent: cpd->m_persistentLifeTime = %i cp.getLifeTime() = %i\n",cpd->m_persistentLifeTime,cp.getLifeTime());
|
||||
|
||||
}
|
||||
} else
|
||||
@@ -191,8 +191,8 @@ void btSequentialImpulseConstraintSolver::PrepareConstraints(btPersistentManifol
|
||||
totalCpd ++;
|
||||
//printf("totalCpd = %i Created Ptr %x\n",totalCpd,cpd);
|
||||
cp.m_userPersistentData = cpd;
|
||||
cpd->m_persistentLifeTime = cp.GetLifeTime();
|
||||
//printf("CREATED: %x . cpd->m_persistentLifeTime = %i cp.GetLifeTime() = %i\n",cpd,cpd->m_persistentLifeTime,cp.GetLifeTime());
|
||||
cpd->m_persistentLifeTime = cp.getLifeTime();
|
||||
//printf("CREATED: %x . cpd->m_persistentLifeTime = %i cp.getLifeTime() = %i\n",cpd,cpd->m_persistentLifeTime,cp.getLifeTime());
|
||||
|
||||
}
|
||||
assert(cpd);
|
||||
@@ -213,7 +213,7 @@ void btSequentialImpulseConstraintSolver::PrepareConstraints(btPersistentManifol
|
||||
|
||||
float combinedRestitution = cp.m_combinedRestitution;
|
||||
|
||||
cpd->m_penetration = cp.GetDistance();
|
||||
cpd->m_penetration = cp.getDistance();
|
||||
cpd->m_friction = cp.m_combinedFriction;
|
||||
cpd->m_restitution = restitutionCurve(rel_vel, combinedRestitution);
|
||||
if (cpd->m_restitution <= 0.) //0.f)
|
||||
@@ -248,14 +248,14 @@ void btSequentialImpulseConstraintSolver::PrepareConstraints(btPersistentManifol
|
||||
cpd->m_accumulatedTangentImpulse0 = 0.f;
|
||||
cpd->m_accumulatedTangentImpulse1 = 0.f;
|
||||
#endif //NO_FRICTION_WARMSTART
|
||||
float denom0 = body0->ComputeImpulseDenominator(pos1,cpd->m_frictionWorldTangential0);
|
||||
float denom1 = body1->ComputeImpulseDenominator(pos2,cpd->m_frictionWorldTangential0);
|
||||
float denom0 = body0->computeImpulseDenominator(pos1,cpd->m_frictionWorldTangential0);
|
||||
float denom1 = body1->computeImpulseDenominator(pos2,cpd->m_frictionWorldTangential0);
|
||||
float denom = relaxation/(denom0+denom1);
|
||||
cpd->m_jacDiagABInvTangent0 = denom;
|
||||
|
||||
|
||||
denom0 = body0->ComputeImpulseDenominator(pos1,cpd->m_frictionWorldTangential1);
|
||||
denom1 = body1->ComputeImpulseDenominator(pos2,cpd->m_frictionWorldTangential1);
|
||||
denom0 = body0->computeImpulseDenominator(pos1,cpd->m_frictionWorldTangential1);
|
||||
denom1 = body1->computeImpulseDenominator(pos2,cpd->m_frictionWorldTangential1);
|
||||
denom = relaxation/(denom0+denom1);
|
||||
cpd->m_jacDiagABInvTangent1 = denom;
|
||||
|
||||
@@ -275,16 +275,16 @@ void btSequentialImpulseConstraintSolver::PrepareConstraints(btPersistentManifol
|
||||
}
|
||||
}
|
||||
|
||||
float btSequentialImpulseConstraintSolver::Solve(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
|
||||
float btSequentialImpulseConstraintSolver::solve(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
|
||||
{
|
||||
|
||||
btRigidBody* body0 = (btRigidBody*)manifoldPtr->GetBody0();
|
||||
btRigidBody* body1 = (btRigidBody*)manifoldPtr->GetBody1();
|
||||
btRigidBody* body0 = (btRigidBody*)manifoldPtr->getBody0();
|
||||
btRigidBody* body1 = (btRigidBody*)manifoldPtr->getBody1();
|
||||
|
||||
float maxImpulse = 0.f;
|
||||
|
||||
{
|
||||
const int numpoints = manifoldPtr->GetNumContacts();
|
||||
const int numpoints = manifoldPtr->getNumContacts();
|
||||
|
||||
btVector3 color(0,1,0);
|
||||
for (int i=0;i<numpoints ;i++)
|
||||
@@ -296,14 +296,14 @@ float btSequentialImpulseConstraintSolver::Solve(btPersistentManifold* manifoldP
|
||||
else
|
||||
j=i;
|
||||
|
||||
btManifoldPoint& cp = manifoldPtr->GetContactPoint(j);
|
||||
if (cp.GetDistance() <= 0.f)
|
||||
btManifoldPoint& cp = manifoldPtr->getContactPoint(j);
|
||||
if (cp.getDistance() <= 0.f)
|
||||
{
|
||||
|
||||
if (iter == 0)
|
||||
{
|
||||
if (debugDrawer)
|
||||
debugDrawer->DrawContactPoint(cp.m_positionWorldOnB,cp.m_normalWorldOnB,cp.GetDistance(),cp.GetLifeTime(),color);
|
||||
debugDrawer->drawContactPoint(cp.m_positionWorldOnB,cp.m_normalWorldOnB,cp.getDistance(),cp.getLifeTime(),color);
|
||||
}
|
||||
|
||||
{
|
||||
@@ -324,14 +324,14 @@ float btSequentialImpulseConstraintSolver::Solve(btPersistentManifold* manifoldP
|
||||
return maxImpulse;
|
||||
}
|
||||
|
||||
float btSequentialImpulseConstraintSolver::SolveFriction(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
|
||||
float btSequentialImpulseConstraintSolver::solveFriction(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer)
|
||||
{
|
||||
btRigidBody* body0 = (btRigidBody*)manifoldPtr->GetBody0();
|
||||
btRigidBody* body1 = (btRigidBody*)manifoldPtr->GetBody1();
|
||||
btRigidBody* body0 = (btRigidBody*)manifoldPtr->getBody0();
|
||||
btRigidBody* body1 = (btRigidBody*)manifoldPtr->getBody1();
|
||||
|
||||
|
||||
{
|
||||
const int numpoints = manifoldPtr->GetNumContacts();
|
||||
const int numpoints = manifoldPtr->getNumContacts();
|
||||
|
||||
btVector3 color(0,1,0);
|
||||
for (int i=0;i<numpoints ;i++)
|
||||
@@ -341,8 +341,8 @@ float btSequentialImpulseConstraintSolver::SolveFriction(btPersistentManifold* m
|
||||
//if (iter % 2)
|
||||
// j = numpoints-1-i;
|
||||
|
||||
btManifoldPoint& cp = manifoldPtr->GetContactPoint(j);
|
||||
if (cp.GetDistance() <= 0.f)
|
||||
btManifoldPoint& cp = manifoldPtr->getContactPoint(j);
|
||||
if (cp.getDistance() <= 0.f)
|
||||
{
|
||||
|
||||
btConstraintPersistentData* cpd = (btConstraintPersistentData*) cp.m_userPersistentData;
|
||||
|
||||
@@ -29,9 +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);
|
||||
void PrepareConstraints(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,btIDebugDraw* debugDrawer);
|
||||
float solve(btPersistentManifold* manifold, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer);
|
||||
float solveFriction(btPersistentManifold* manifoldPtr, 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];
|
||||
ContactSolverFunc m_frictionDispatch[MAX_CONTACT_SOLVER_TYPES][MAX_CONTACT_SOLVER_TYPES];
|
||||
@@ -42,7 +42,7 @@ public:
|
||||
|
||||
///Advanced: Override the default contact solving function for contacts, for certain types of rigidbody
|
||||
///See btRigidBody::m_contactSolverType and btRigidBody::m_frictionSolverType
|
||||
void SetContactSolverFunc(ContactSolverFunc func,int type0,int type1)
|
||||
void setContactSolverFunc(ContactSolverFunc func,int type0,int type1)
|
||||
{
|
||||
m_contactDispatch[type0][type1] = func;
|
||||
}
|
||||
@@ -56,7 +56,7 @@ public:
|
||||
|
||||
virtual ~btSequentialImpulseConstraintSolver() {}
|
||||
|
||||
virtual float SolveGroup(btPersistentManifold** manifold,int numManifolds,const btContactSolverInfo& info, btIDebugDraw* debugDrawer=0);
|
||||
virtual float solveGroup(btPersistentManifold** manifold,int numManifolds,const btContactSolverInfo& info, btIDebugDraw* debugDrawer=0);
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -40,48 +40,48 @@ public:
|
||||
|
||||
btTypedConstraint(btRigidBody& rbA,btRigidBody& rbB);
|
||||
|
||||
virtual void BuildJacobian() = 0;
|
||||
virtual void buildJacobian() = 0;
|
||||
|
||||
virtual void SolveConstraint(btScalar timeStep) = 0;
|
||||
virtual void solveConstraint(btScalar timeStep) = 0;
|
||||
|
||||
const btRigidBody& GetRigidBodyA() const
|
||||
const btRigidBody& getRigidBodyA() const
|
||||
{
|
||||
return m_rbA;
|
||||
}
|
||||
const btRigidBody& GetRigidBodyB() const
|
||||
const btRigidBody& getRigidBodyB() const
|
||||
{
|
||||
return m_rbB;
|
||||
}
|
||||
|
||||
btRigidBody& GetRigidBodyA()
|
||||
btRigidBody& getRigidBodyA()
|
||||
{
|
||||
return m_rbA;
|
||||
}
|
||||
btRigidBody& GetRigidBodyB()
|
||||
btRigidBody& getRigidBodyB()
|
||||
{
|
||||
return m_rbB;
|
||||
}
|
||||
|
||||
int GetUserConstraintType() const
|
||||
int getUserConstraintType() const
|
||||
{
|
||||
return m_userConstraintType ;
|
||||
}
|
||||
|
||||
void SetUserConstraintType(int userConstraintType)
|
||||
void setUserConstraintType(int userConstraintType)
|
||||
{
|
||||
m_userConstraintType = userConstraintType;
|
||||
};
|
||||
|
||||
void SetUserConstraintId(int uid)
|
||||
void setUserConstraintId(int uid)
|
||||
{
|
||||
m_userConstraintId = uid;
|
||||
}
|
||||
|
||||
int GetUserConstraintId()
|
||||
int getUserConstraintId()
|
||||
{
|
||||
return m_userConstraintId;
|
||||
}
|
||||
float GetAppliedImpulse()
|
||||
float getAppliedImpulse()
|
||||
{
|
||||
return m_appliedImpulse;
|
||||
}
|
||||
|
||||
@@ -72,7 +72,7 @@ void btDiscreteDynamicsWorld::stepSimulation(float timeStep)
|
||||
predictUnconstraintMotion(timeStep);
|
||||
|
||||
///perform collision detection
|
||||
PerformDiscreteCollisionDetection();
|
||||
performDiscreteCollisionDetection();
|
||||
|
||||
calculateSimulationIslands();
|
||||
|
||||
@@ -104,7 +104,7 @@ void btDiscreteDynamicsWorld::updateVehicles(float timeStep)
|
||||
for (int i=0;i<m_vehicles.size();i++)
|
||||
{
|
||||
btRaycastVehicle* vehicle = m_vehicles[i];
|
||||
vehicle->UpdateVehicle( timeStep);
|
||||
vehicle->updateVehicle( timeStep);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -184,7 +184,7 @@ void btDiscreteDynamicsWorld::solveContactConstraints(btContactSolverInfo& solve
|
||||
|
||||
virtual void ProcessIsland(btPersistentManifold** manifolds,int numManifolds)
|
||||
{
|
||||
m_solver->SolveGroup( manifolds, numManifolds,m_solverInfo,m_debugDrawer);
|
||||
m_solver->solveGroup( manifolds, numManifolds,m_solverInfo,m_debugDrawer);
|
||||
}
|
||||
|
||||
};
|
||||
@@ -194,7 +194,7 @@ void btDiscreteDynamicsWorld::solveContactConstraints(btContactSolverInfo& solve
|
||||
|
||||
|
||||
/// solve all the contact points and contact friction
|
||||
m_islandManager->BuildAndProcessIslands(GetCollisionWorld()->GetDispatcher(),GetCollisionWorld()->GetCollisionObjectArray(),&solverCallback);
|
||||
m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(),getCollisionWorld()->getCollisionObjectArray(),&solverCallback);
|
||||
|
||||
|
||||
}
|
||||
@@ -203,7 +203,7 @@ void btDiscreteDynamicsWorld::solveContactConstraints(btContactSolverInfo& solve
|
||||
void btDiscreteDynamicsWorld::solveNoncontactConstraints(btContactSolverInfo& solverInfo)
|
||||
{
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::beginBlock("SolveConstraint");
|
||||
Profiler::beginBlock("solveConstraint");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
|
||||
@@ -215,7 +215,7 @@ void btDiscreteDynamicsWorld::solveNoncontactConstraints(btContactSolverInfo& so
|
||||
for (i=0;i< numConstraints ; i++ )
|
||||
{
|
||||
btTypedConstraint* constraint = m_constraints[i];
|
||||
constraint->BuildJacobian();
|
||||
constraint->buildJacobian();
|
||||
}
|
||||
|
||||
//solve the regular non-contact constraints (point 2 point, hinge, generic d6)
|
||||
@@ -227,12 +227,12 @@ void btDiscreteDynamicsWorld::solveNoncontactConstraints(btContactSolverInfo& so
|
||||
for (i=0;i< numConstraints ; i++ )
|
||||
{
|
||||
btTypedConstraint* constraint = m_constraints[i];
|
||||
constraint->SolveConstraint( solverInfo.m_timeStep );
|
||||
constraint->solveConstraint( solverInfo.m_timeStep );
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("SolveConstraint");
|
||||
Profiler::endBlock("solveConstraint");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
}
|
||||
@@ -244,7 +244,7 @@ void btDiscreteDynamicsWorld::calculateSimulationIslands()
|
||||
Profiler::beginBlock("IslandUnionFind");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
GetSimulationIslandManager()->UpdateActivationState(GetCollisionWorld(),GetCollisionWorld()->GetDispatcher());
|
||||
getSimulationIslandManager()->updateActivationState(getCollisionWorld(),getCollisionWorld()->getDispatcher());
|
||||
|
||||
{
|
||||
int i;
|
||||
@@ -253,8 +253,8 @@ void btDiscreteDynamicsWorld::calculateSimulationIslands()
|
||||
{
|
||||
btTypedConstraint* constraint = m_constraints[i];
|
||||
|
||||
const btRigidBody* colObj0 = &constraint->GetRigidBodyA();
|
||||
const btRigidBody* colObj1 = &constraint->GetRigidBodyB();
|
||||
const btRigidBody* colObj0 = &constraint->getRigidBodyA();
|
||||
const btRigidBody* colObj1 = &constraint->getRigidBodyB();
|
||||
|
||||
if (((colObj0) && ((colObj0)->mergesSimulationIslands())) &&
|
||||
((colObj1) && ((colObj1)->mergesSimulationIslands())))
|
||||
@@ -262,7 +262,7 @@ void btDiscreteDynamicsWorld::calculateSimulationIslands()
|
||||
if (colObj0->IsActive() || colObj1->IsActive())
|
||||
{
|
||||
|
||||
GetSimulationIslandManager()->GetUnionFind().unite((colObj0)->m_islandTag1,
|
||||
getSimulationIslandManager()->getUnionFind().unite((colObj0)->m_islandTag1,
|
||||
(colObj1)->m_islandTag1);
|
||||
}
|
||||
}
|
||||
@@ -270,7 +270,7 @@ void btDiscreteDynamicsWorld::calculateSimulationIslands()
|
||||
}
|
||||
|
||||
//Store the island id in each body
|
||||
GetSimulationIslandManager()->StoreIslandActivationState(GetCollisionWorld());
|
||||
getSimulationIslandManager()->storeIslandActivationState(getCollisionWorld());
|
||||
|
||||
#ifdef USE_QUICKPROF
|
||||
Profiler::endBlock("IslandUnionFind");
|
||||
@@ -290,9 +290,9 @@ void btDiscreteDynamicsWorld::updateAabbs()
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
btPoint3 minAabb,maxAabb;
|
||||
colObj->m_collisionShape->GetAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_pairCache;
|
||||
bp->SetAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -77,17 +77,17 @@ public:
|
||||
|
||||
void removeVehicle(btRaycastVehicle* vehicle);
|
||||
|
||||
btSimulationIslandManager* GetSimulationIslandManager()
|
||||
btSimulationIslandManager* getSimulationIslandManager()
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
const btSimulationIslandManager* GetSimulationIslandManager() const
|
||||
const btSimulationIslandManager* getSimulationIslandManager() const
|
||||
{
|
||||
return m_islandManager;
|
||||
}
|
||||
|
||||
btCollisionWorld* GetCollisionWorld()
|
||||
btCollisionWorld* getCollisionWorld()
|
||||
{
|
||||
return this;
|
||||
}
|
||||
|
||||
@@ -60,7 +60,7 @@ void btRigidBody::setLinearVelocity(const btVector3& lin_vel)
|
||||
|
||||
void btRigidBody::predictIntegratedTransform(btScalar timeStep,btTransform& predictedTransform) const
|
||||
{
|
||||
btTransformUtil::IntegrateTransform(m_worldTransform,m_linearVelocity,m_angularVelocity,timeStep,predictedTransform);
|
||||
btTransformUtil::integrateTransform(m_worldTransform,m_linearVelocity,m_angularVelocity,timeStep,predictedTransform);
|
||||
}
|
||||
|
||||
void btRigidBody::saveKinematicState(btScalar timeStep)
|
||||
@@ -69,7 +69,7 @@ void btRigidBody::saveKinematicState(btScalar timeStep)
|
||||
if (m_kinematicTimeStep)
|
||||
{
|
||||
btVector3 linVel,angVel;
|
||||
btTransformUtil::CalculateVelocity(m_interpolationWorldTransform,m_worldTransform,m_kinematicTimeStep,m_linearVelocity,m_angularVelocity);
|
||||
btTransformUtil::calculateVelocity(m_interpolationWorldTransform,m_worldTransform,m_kinematicTimeStep,m_linearVelocity,m_angularVelocity);
|
||||
//printf("angular = %f %f %f\n",m_angularVelocity.getX(),m_angularVelocity.getY(),m_angularVelocity.getZ());
|
||||
}
|
||||
|
||||
@@ -81,7 +81,7 @@ void btRigidBody::saveKinematicState(btScalar timeStep)
|
||||
|
||||
void btRigidBody::getAabb(btVector3& aabbMin,btVector3& aabbMax) const
|
||||
{
|
||||
GetCollisionShape()->GetAabb(m_worldTransform,aabbMin,aabbMax);
|
||||
getCollisionShape()->getAabb(m_worldTransform,aabbMin,aabbMax);
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -78,11 +78,11 @@ public:
|
||||
|
||||
void setDamping(btScalar lin_damping, btScalar ang_damping);
|
||||
|
||||
inline const btCollisionShape* GetCollisionShape() const {
|
||||
inline const btCollisionShape* getCollisionShape() const {
|
||||
return m_collisionShape;
|
||||
}
|
||||
|
||||
inline btCollisionShape* GetCollisionShape() {
|
||||
inline btCollisionShape* getCollisionShape() {
|
||||
return m_collisionShape;
|
||||
}
|
||||
|
||||
@@ -197,7 +197,7 @@ public:
|
||||
|
||||
|
||||
|
||||
inline float ComputeImpulseDenominator(const btPoint3& pos, const btVector3& normal) const
|
||||
inline float computeImpulseDenominator(const btPoint3& pos, const btVector3& normal) const
|
||||
{
|
||||
btVector3 r0 = pos - getCenterOfMassPosition();
|
||||
|
||||
@@ -209,7 +209,7 @@ public:
|
||||
|
||||
}
|
||||
|
||||
inline float ComputeAngularImpulseDenominator(const btVector3& axis) const
|
||||
inline float computeAngularImpulseDenominator(const btVector3& axis) const
|
||||
{
|
||||
btVector3 vec = axis * getInvInertiaTensorWorld();
|
||||
return axis.dot(vec);
|
||||
@@ -254,15 +254,15 @@ public:
|
||||
|
||||
|
||||
|
||||
const btBroadphaseProxy* GetBroadphaseProxy() const
|
||||
const btBroadphaseProxy* getBroadphaseProxy() const
|
||||
{
|
||||
return m_broadphaseProxy;
|
||||
}
|
||||
btBroadphaseProxy* GetBroadphaseProxy()
|
||||
btBroadphaseProxy* getBroadphaseProxy()
|
||||
{
|
||||
return m_broadphaseProxy;
|
||||
}
|
||||
void SetBroadphaseProxy(btBroadphaseProxy* broadphaseProxy)
|
||||
void setBroadphaseProxy(btBroadphaseProxy* broadphaseProxy)
|
||||
{
|
||||
m_broadphaseProxy = broadphaseProxy;
|
||||
}
|
||||
|
||||
@@ -54,15 +54,15 @@ void btSimpleDynamicsWorld::stepSimulation(float timeStep)
|
||||
predictUnconstraintMotion(timeStep);
|
||||
|
||||
///perform collision detection
|
||||
PerformDiscreteCollisionDetection();
|
||||
performDiscreteCollisionDetection();
|
||||
|
||||
///solve contact constraints
|
||||
btPersistentManifold** manifoldPtr = ((btCollisionDispatcher*)m_dispatcher1)->getInternalManifoldPointer();
|
||||
int numManifolds = m_dispatcher1->GetNumManifolds();
|
||||
int numManifolds = m_dispatcher1->getNumManifolds();
|
||||
btContactSolverInfo infoGlobal;
|
||||
infoGlobal.m_timeStep = timeStep;
|
||||
btIDebugDraw* debugDrawer=0;
|
||||
m_constraintSolver->SolveGroup(manifoldPtr, numManifolds,infoGlobal,debugDrawer);
|
||||
m_constraintSolver->solveGroup(manifoldPtr, numManifolds,infoGlobal,debugDrawer);
|
||||
|
||||
///integrate transforms
|
||||
integrateTransforms(timeStep);
|
||||
@@ -85,9 +85,9 @@ void btSimpleDynamicsWorld::updateAabbs()
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
btPoint3 minAabb,maxAabb;
|
||||
colObj->m_collisionShape->GetAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_pairCache;
|
||||
bp->SetAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -33,11 +33,11 @@ m_pitchControl(0.f)
|
||||
m_indexRightAxis = 0;
|
||||
m_indexUpAxis = 2;
|
||||
m_indexForwardAxis = 1;
|
||||
DefaultInit(tuning);
|
||||
defaultInit(tuning);
|
||||
}
|
||||
|
||||
|
||||
void btRaycastVehicle::DefaultInit(const btVehicleTuning& tuning)
|
||||
void btRaycastVehicle::defaultInit(const btVehicleTuning& tuning)
|
||||
{
|
||||
m_currentVehicleSpeedKmHour = 0.f;
|
||||
m_steeringValue = 0.f;
|
||||
@@ -54,7 +54,7 @@ btRaycastVehicle::~btRaycastVehicle()
|
||||
//
|
||||
// basically most of the code is general for 2 or 4 wheel vehicles, but some of it needs to be reviewed
|
||||
//
|
||||
btWheelInfo& btRaycastVehicle::AddWheel( const btVector3& connectionPointCS, const btVector3& wheelDirectionCS0,const btVector3& wheelAxleCS, btScalar suspensionRestLength, btScalar wheelRadius,const btVehicleTuning& tuning, bool isFrontWheel)
|
||||
btWheelInfo& btRaycastVehicle::addWheel( const btVector3& connectionPointCS, const btVector3& wheelDirectionCS0,const btVector3& wheelAxleCS, btScalar suspensionRestLength, btScalar wheelRadius,const btVehicleTuning& tuning, bool isFrontWheel)
|
||||
{
|
||||
|
||||
btWheelInfoConstructionInfo ci;
|
||||
@@ -73,29 +73,29 @@ btWheelInfo& btRaycastVehicle::AddWheel( const btVector3& connectionPointCS, con
|
||||
|
||||
m_wheelInfo.push_back( btWheelInfo(ci));
|
||||
|
||||
btWheelInfo& wheel = m_wheelInfo[GetNumWheels()-1];
|
||||
btWheelInfo& wheel = m_wheelInfo[getNumWheels()-1];
|
||||
|
||||
UpdateWheelTransformsWS( wheel );
|
||||
UpdateWheelTransform(GetNumWheels()-1);
|
||||
updateWheelTransformsWS( wheel );
|
||||
updateWheelTransform(getNumWheels()-1);
|
||||
return wheel;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
const btTransform& btRaycastVehicle::GetWheelTransformWS( int wheelIndex ) const
|
||||
const btTransform& btRaycastVehicle::getWheelTransformWS( int wheelIndex ) const
|
||||
{
|
||||
assert(wheelIndex < GetNumWheels());
|
||||
assert(wheelIndex < getNumWheels());
|
||||
const btWheelInfo& wheel = m_wheelInfo[wheelIndex];
|
||||
return wheel.m_worldTransform;
|
||||
|
||||
}
|
||||
|
||||
void btRaycastVehicle::UpdateWheelTransform( int wheelIndex )
|
||||
void btRaycastVehicle::updateWheelTransform( int wheelIndex )
|
||||
{
|
||||
|
||||
btWheelInfo& wheel = m_wheelInfo[ wheelIndex ];
|
||||
UpdateWheelTransformsWS(wheel);
|
||||
updateWheelTransformsWS(wheel);
|
||||
btVector3 up = -wheel.m_raycastInfo.m_wheelDirectionWS;
|
||||
const btVector3& right = wheel.m_raycastInfo.m_wheelAxleWS;
|
||||
btVector3 fwd = up.cross(right);
|
||||
@@ -121,7 +121,7 @@ void btRaycastVehicle::UpdateWheelTransform( int wheelIndex )
|
||||
);
|
||||
}
|
||||
|
||||
void btRaycastVehicle::ResetSuspension()
|
||||
void btRaycastVehicle::resetSuspension()
|
||||
{
|
||||
|
||||
std::vector<btWheelInfo>::iterator wheelIt;
|
||||
@@ -129,7 +129,7 @@ void btRaycastVehicle::ResetSuspension()
|
||||
!(wheelIt == m_wheelInfo.end());wheelIt++)
|
||||
{
|
||||
btWheelInfo& wheel = *wheelIt;
|
||||
wheel.m_raycastInfo.m_suspensionLength = wheel.GetSuspensionRestLength();
|
||||
wheel.m_raycastInfo.m_suspensionLength = wheel.getSuspensionRestLength();
|
||||
wheel.m_suspensionRelativeVelocity = 0.0f;
|
||||
|
||||
wheel.m_raycastInfo.m_contactNormalWS = - wheel.m_raycastInfo.m_wheelDirectionWS;
|
||||
@@ -138,25 +138,25 @@ void btRaycastVehicle::ResetSuspension()
|
||||
}
|
||||
}
|
||||
|
||||
void btRaycastVehicle::UpdateWheelTransformsWS(btWheelInfo& wheel )
|
||||
void btRaycastVehicle::updateWheelTransformsWS(btWheelInfo& wheel )
|
||||
{
|
||||
wheel.m_raycastInfo.m_isInContact = false;
|
||||
|
||||
const btTransform& chassisTrans = GetRigidBody()->getCenterOfMassTransform();
|
||||
const btTransform& 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;
|
||||
}
|
||||
|
||||
btScalar btRaycastVehicle::Raycast(btWheelInfo& wheel)
|
||||
btScalar btRaycastVehicle::rayCast(btWheelInfo& wheel)
|
||||
{
|
||||
UpdateWheelTransformsWS( wheel );
|
||||
updateWheelTransformsWS( wheel );
|
||||
|
||||
|
||||
btScalar depth = -1;
|
||||
|
||||
btScalar raylen = wheel.GetSuspensionRestLength()+wheel.m_wheelsRadius;
|
||||
btScalar raylen = wheel.getSuspensionRestLength()+wheel.m_wheelsRadius;
|
||||
|
||||
btVector3 rayvector = wheel.m_raycastInfo.m_wheelDirectionWS * (raylen);
|
||||
const btVector3& source = wheel.m_raycastInfo.m_hardPointWS;
|
||||
@@ -167,7 +167,7 @@ btScalar btRaycastVehicle::Raycast(btWheelInfo& wheel)
|
||||
|
||||
btVehicleRaycaster::btVehicleRaycasterResult rayResults;
|
||||
|
||||
void* object = m_vehicleRaycaster->CastRay(source,target,rayResults);
|
||||
void* object = m_vehicleRaycaster->castRay(source,target,rayResults);
|
||||
|
||||
wheel.m_raycastInfo.m_groundObject = 0;
|
||||
|
||||
@@ -186,8 +186,8 @@ btScalar btRaycastVehicle::Raycast(btWheelInfo& wheel)
|
||||
wheel.m_raycastInfo.m_suspensionLength = hitDistance - wheel.m_wheelsRadius;
|
||||
//clamp on max suspension travel
|
||||
|
||||
float minSuspensionLength = wheel.GetSuspensionRestLength() - wheel.m_maxSuspensionTravelCm*0.01f;
|
||||
float maxSuspensionLength = wheel.GetSuspensionRestLength()+ wheel.m_maxSuspensionTravelCm*0.01f;
|
||||
float minSuspensionLength = wheel.getSuspensionRestLength() - wheel.m_maxSuspensionTravelCm*0.01f;
|
||||
float maxSuspensionLength = wheel.getSuspensionRestLength()+ wheel.m_maxSuspensionTravelCm*0.01f;
|
||||
if (wheel.m_raycastInfo.m_suspensionLength < minSuspensionLength)
|
||||
{
|
||||
wheel.m_raycastInfo.m_suspensionLength = minSuspensionLength;
|
||||
@@ -202,9 +202,9 @@ btScalar btRaycastVehicle::Raycast(btWheelInfo& wheel)
|
||||
btScalar denominator= wheel.m_raycastInfo.m_contactNormalWS.dot( wheel.m_raycastInfo.m_wheelDirectionWS );
|
||||
|
||||
btVector3 chassis_velocity_at_contactPoint;
|
||||
btVector3 relpos = wheel.m_raycastInfo.m_contactPointWS-GetRigidBody()->getCenterOfMassPosition();
|
||||
btVector3 relpos = wheel.m_raycastInfo.m_contactPointWS-getRigidBody()->getCenterOfMassPosition();
|
||||
|
||||
chassis_velocity_at_contactPoint = GetRigidBody()->getVelocityInLocalPoint(relpos);
|
||||
chassis_velocity_at_contactPoint = getRigidBody()->getVelocityInLocalPoint(relpos);
|
||||
|
||||
btScalar projVel = wheel.m_raycastInfo.m_contactNormalWS.dot( chassis_velocity_at_contactPoint );
|
||||
|
||||
@@ -223,7 +223,7 @@ btScalar btRaycastVehicle::Raycast(btWheelInfo& wheel)
|
||||
} else
|
||||
{
|
||||
//put wheel info as in rest position
|
||||
wheel.m_raycastInfo.m_suspensionLength = wheel.GetSuspensionRestLength();
|
||||
wheel.m_raycastInfo.m_suspensionLength = wheel.getSuspensionRestLength();
|
||||
wheel.m_suspensionRelativeVelocity = 0.0f;
|
||||
wheel.m_raycastInfo.m_contactNormalWS = - wheel.m_raycastInfo.m_wheelDirectionWS;
|
||||
wheel.m_clippedInvContactDotSuspension = 1.0f;
|
||||
@@ -233,18 +233,18 @@ btScalar btRaycastVehicle::Raycast(btWheelInfo& wheel)
|
||||
}
|
||||
|
||||
|
||||
void btRaycastVehicle::UpdateVehicle( btScalar step )
|
||||
void btRaycastVehicle::updateVehicle( btScalar step )
|
||||
{
|
||||
|
||||
m_currentVehicleSpeedKmHour = 3.6f * GetRigidBody()->getLinearVelocity().length();
|
||||
m_currentVehicleSpeedKmHour = 3.6f * getRigidBody()->getLinearVelocity().length();
|
||||
|
||||
const btTransform& chassisTrans = GetRigidBody()->getCenterOfMassTransform();
|
||||
const btTransform& chassisTrans = getRigidBody()->getCenterOfMassTransform();
|
||||
btVector3 forwardW (
|
||||
chassisTrans.getBasis()[0][m_indexForwardAxis],
|
||||
chassisTrans.getBasis()[1][m_indexForwardAxis],
|
||||
chassisTrans.getBasis()[2][m_indexForwardAxis]);
|
||||
|
||||
if (forwardW.dot(GetRigidBody()->getLinearVelocity()) < 0.f)
|
||||
if (forwardW.dot(getRigidBody()->getLinearVelocity()) < 0.f)
|
||||
{
|
||||
m_currentVehicleSpeedKmHour *= -1.f;
|
||||
}
|
||||
@@ -258,10 +258,10 @@ void btRaycastVehicle::UpdateVehicle( btScalar step )
|
||||
!(wheelIt == m_wheelInfo.end());wheelIt++,i++)
|
||||
{
|
||||
btScalar depth;
|
||||
depth = Raycast( *wheelIt );
|
||||
depth = rayCast( *wheelIt );
|
||||
}
|
||||
|
||||
UpdateSuspension(step);
|
||||
updateSuspension(step);
|
||||
|
||||
|
||||
for (wheelIt = m_wheelInfo.begin();
|
||||
@@ -278,30 +278,30 @@ void btRaycastVehicle::UpdateVehicle( btScalar step )
|
||||
suspensionForce = gMaxSuspensionForce;
|
||||
}
|
||||
btVector3 impulse = wheel.m_raycastInfo.m_contactNormalWS * suspensionForce * step;
|
||||
btVector3 relpos = wheel.m_raycastInfo.m_contactPointWS - GetRigidBody()->getCenterOfMassPosition();
|
||||
btVector3 relpos = wheel.m_raycastInfo.m_contactPointWS - getRigidBody()->getCenterOfMassPosition();
|
||||
|
||||
GetRigidBody()->applyImpulse(impulse, relpos);
|
||||
getRigidBody()->applyImpulse(impulse, relpos);
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
UpdateFriction( step);
|
||||
updateFriction( step);
|
||||
|
||||
|
||||
for (wheelIt = m_wheelInfo.begin();
|
||||
!(wheelIt == m_wheelInfo.end());wheelIt++)
|
||||
{
|
||||
btWheelInfo& wheel = *wheelIt;
|
||||
btVector3 relpos = wheel.m_raycastInfo.m_hardPointWS - GetRigidBody()->getCenterOfMassPosition();
|
||||
btVector3 vel = GetRigidBody()->getVelocityInLocalPoint( relpos );
|
||||
btVector3 relpos = wheel.m_raycastInfo.m_hardPointWS - getRigidBody()->getCenterOfMassPosition();
|
||||
btVector3 vel = getRigidBody()->getVelocityInLocalPoint( relpos );
|
||||
|
||||
if (wheel.m_raycastInfo.m_isInContact)
|
||||
{
|
||||
btVector3 fwd (
|
||||
GetRigidBody()->getCenterOfMassTransform().getBasis()[0][m_indexForwardAxis],
|
||||
GetRigidBody()->getCenterOfMassTransform().getBasis()[1][m_indexForwardAxis],
|
||||
GetRigidBody()->getCenterOfMassTransform().getBasis()[2][m_indexForwardAxis]);
|
||||
getRigidBody()->getCenterOfMassTransform().getBasis()[0][m_indexForwardAxis],
|
||||
getRigidBody()->getCenterOfMassTransform().getBasis()[1][m_indexForwardAxis],
|
||||
getRigidBody()->getCenterOfMassTransform().getBasis()[2][m_indexForwardAxis]);
|
||||
|
||||
btScalar proj = fwd.dot(wheel.m_raycastInfo.m_contactNormalWS);
|
||||
fwd -= wheel.m_raycastInfo.m_contactNormalWS * proj;
|
||||
@@ -325,57 +325,57 @@ void btRaycastVehicle::UpdateVehicle( btScalar step )
|
||||
}
|
||||
|
||||
|
||||
void btRaycastVehicle::SetSteeringValue(btScalar steering,int wheel)
|
||||
void btRaycastVehicle::setSteeringValue(btScalar steering,int wheel)
|
||||
{
|
||||
assert(wheel>=0 && wheel < GetNumWheels());
|
||||
assert(wheel>=0 && wheel < getNumWheels());
|
||||
|
||||
btWheelInfo& wheelInfo = GetWheelInfo(wheel);
|
||||
btWheelInfo& wheelInfo = getWheelInfo(wheel);
|
||||
wheelInfo.m_steering = steering;
|
||||
}
|
||||
|
||||
|
||||
|
||||
btScalar btRaycastVehicle::GetSteeringValue(int wheel) const
|
||||
btScalar btRaycastVehicle::getSteeringValue(int wheel) const
|
||||
{
|
||||
return GetWheelInfo(wheel).m_steering;
|
||||
return getWheelInfo(wheel).m_steering;
|
||||
}
|
||||
|
||||
|
||||
void btRaycastVehicle::ApplyEngineForce(btScalar force, int wheel)
|
||||
void btRaycastVehicle::applyEngineForce(btScalar force, int wheel)
|
||||
{
|
||||
assert(wheel>=0 && wheel < GetNumWheels());
|
||||
btWheelInfo& wheelInfo = GetWheelInfo(wheel);
|
||||
assert(wheel>=0 && wheel < getNumWheels());
|
||||
btWheelInfo& wheelInfo = getWheelInfo(wheel);
|
||||
wheelInfo.m_engineForce = force;
|
||||
}
|
||||
|
||||
|
||||
const btWheelInfo& btRaycastVehicle::GetWheelInfo(int index) const
|
||||
const btWheelInfo& btRaycastVehicle::getWheelInfo(int index) const
|
||||
{
|
||||
ASSERT((index >= 0) && (index < GetNumWheels()));
|
||||
ASSERT((index >= 0) && (index < getNumWheels()));
|
||||
|
||||
return m_wheelInfo[index];
|
||||
}
|
||||
|
||||
btWheelInfo& btRaycastVehicle::GetWheelInfo(int index)
|
||||
btWheelInfo& btRaycastVehicle::getWheelInfo(int index)
|
||||
{
|
||||
ASSERT((index >= 0) && (index < GetNumWheels()));
|
||||
ASSERT((index >= 0) && (index < getNumWheels()));
|
||||
|
||||
return m_wheelInfo[index];
|
||||
}
|
||||
|
||||
void btRaycastVehicle::SetBrake(float brake,int wheelIndex)
|
||||
void btRaycastVehicle::setBrake(float brake,int wheelIndex)
|
||||
{
|
||||
ASSERT((wheelIndex >= 0) && (wheelIndex < GetNumWheels()));
|
||||
GetWheelInfo(wheelIndex).m_brake;
|
||||
ASSERT((wheelIndex >= 0) && (wheelIndex < getNumWheels()));
|
||||
getWheelInfo(wheelIndex).m_brake;
|
||||
}
|
||||
|
||||
|
||||
void btRaycastVehicle::UpdateSuspension(btScalar deltaTime)
|
||||
void btRaycastVehicle::updateSuspension(btScalar deltaTime)
|
||||
{
|
||||
|
||||
btScalar chassisMass = 1.f / m_chassisBody->getInvMass();
|
||||
|
||||
for (int w_it=0; w_it<GetNumWheels(); w_it++)
|
||||
for (int w_it=0; w_it<getNumWheels(); w_it++)
|
||||
{
|
||||
btWheelInfo &wheel_info = m_wheelInfo[w_it];
|
||||
|
||||
@@ -384,7 +384,7 @@ void btRaycastVehicle::UpdateSuspension(btScalar deltaTime)
|
||||
btScalar force;
|
||||
// Spring
|
||||
{
|
||||
btScalar susp_length = wheel_info.GetSuspensionRestLength();
|
||||
btScalar susp_length = wheel_info.getSuspensionRestLength();
|
||||
btScalar current_length = wheel_info.m_raycastInfo.m_suspensionLength;
|
||||
|
||||
btScalar length_diff = (susp_length - current_length);
|
||||
@@ -426,11 +426,11 @@ void btRaycastVehicle::UpdateSuspension(btScalar deltaTime)
|
||||
}
|
||||
|
||||
float sideFrictionStiffness2 = 1.0f;
|
||||
void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
void btRaycastVehicle::updateFriction(btScalar timeStep)
|
||||
{
|
||||
|
||||
//calculate the impulse, so that the wheels don't move sidewards
|
||||
int numWheel = GetNumWheels();
|
||||
int numWheel = getNumWheels();
|
||||
if (!numWheel)
|
||||
return;
|
||||
|
||||
@@ -444,7 +444,7 @@ void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
|
||||
|
||||
//collapse all those loops into one!
|
||||
for (int i=0;i<GetNumWheels();i++)
|
||||
for (int i=0;i<getNumWheels();i++)
|
||||
{
|
||||
btWheelInfo& wheelInfo = m_wheelInfo[i];
|
||||
class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
|
||||
@@ -457,7 +457,7 @@ void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
|
||||
{
|
||||
|
||||
for (int i=0;i<GetNumWheels();i++)
|
||||
for (int i=0;i<getNumWheels();i++)
|
||||
{
|
||||
|
||||
btWheelInfo& wheelInfo = m_wheelInfo[i];
|
||||
@@ -467,7 +467,7 @@ void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
if (groundObject)
|
||||
{
|
||||
|
||||
const btTransform& wheelTrans = GetWheelTransformWS( i );
|
||||
const btTransform& wheelTrans = getWheelTransformWS( i );
|
||||
|
||||
btMatrix3x3 wheelBasis0 = wheelTrans.getBasis();
|
||||
axle[i] = btVector3(
|
||||
@@ -501,7 +501,7 @@ void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
|
||||
bool sliding = false;
|
||||
{
|
||||
for (int wheel =0;wheel <GetNumWheels();wheel++)
|
||||
for (int wheel =0;wheel <getNumWheels();wheel++)
|
||||
{
|
||||
btWheelInfo& wheelInfo = m_wheelInfo[wheel];
|
||||
class btRigidBody* groundObject = (class btRigidBody*) wheelInfo.m_raycastInfo.m_groundObject;
|
||||
@@ -544,7 +544,7 @@ void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
|
||||
if (sliding)
|
||||
{
|
||||
for (int wheel = 0;wheel < GetNumWheels(); wheel++)
|
||||
for (int wheel = 0;wheel < getNumWheels(); wheel++)
|
||||
{
|
||||
if (sideImpulse[wheel] != 0.f)
|
||||
{
|
||||
@@ -559,7 +559,7 @@ void btRaycastVehicle::UpdateFriction(btScalar timeStep)
|
||||
|
||||
// apply the impulses
|
||||
{
|
||||
for (int wheel = 0;wheel<GetNumWheels() ; wheel++)
|
||||
for (int wheel = 0;wheel<getNumWheels() ; wheel++)
|
||||
{
|
||||
btWheelInfo& wheelInfo = m_wheelInfo[wheel];
|
||||
|
||||
|
||||
@@ -20,7 +20,7 @@ struct btMassProps;
|
||||
struct btVehicleRaycaster;
|
||||
class btVehicleTuning;
|
||||
|
||||
///Raycast vehicle, very special constraint that turn a rigidbody into a vehicle.
|
||||
///rayCast vehicle, very special constraint that turn a rigidbody into a vehicle.
|
||||
class btRaycastVehicle : public btTypedConstraint
|
||||
{
|
||||
public:
|
||||
@@ -58,7 +58,7 @@ private:
|
||||
int m_indexUpAxis;
|
||||
int m_indexForwardAxis;
|
||||
|
||||
void DefaultInit(const btVehicleTuning& tuning);
|
||||
void defaultInit(const btVehicleTuning& tuning);
|
||||
|
||||
public:
|
||||
|
||||
@@ -71,91 +71,91 @@ public:
|
||||
|
||||
|
||||
|
||||
btScalar Raycast(btWheelInfo& wheel);
|
||||
btScalar rayCast(btWheelInfo& wheel);
|
||||
|
||||
virtual void UpdateVehicle(btScalar step);
|
||||
virtual void updateVehicle(btScalar step);
|
||||
|
||||
void ResetSuspension();
|
||||
void resetSuspension();
|
||||
|
||||
btScalar GetSteeringValue(int wheel) const;
|
||||
btScalar getSteeringValue(int wheel) const;
|
||||
|
||||
void SetSteeringValue(btScalar steering,int wheel);
|
||||
void setSteeringValue(btScalar steering,int wheel);
|
||||
|
||||
|
||||
void ApplyEngineForce(btScalar force, int wheel);
|
||||
void applyEngineForce(btScalar force, int wheel);
|
||||
|
||||
const btTransform& GetWheelTransformWS( int wheelIndex ) const;
|
||||
const btTransform& getWheelTransformWS( int wheelIndex ) const;
|
||||
|
||||
void UpdateWheelTransform( int wheelIndex );
|
||||
void updateWheelTransform( int wheelIndex );
|
||||
|
||||
void SetRaycastWheelInfo( int wheelIndex , bool isInContact, const btVector3& hitPoint, const btVector3& hitNormal,btScalar depth);
|
||||
void setRaycastWheelInfo( int wheelIndex , bool isInContact, const btVector3& hitPoint, const btVector3& hitNormal,btScalar depth);
|
||||
|
||||
btWheelInfo& AddWheel( const btVector3& connectionPointCS0, const btVector3& wheelDirectionCS0,const btVector3& wheelAxleCS,btScalar suspensionRestLength,btScalar wheelRadius,const btVehicleTuning& tuning, bool isFrontWheel);
|
||||
btWheelInfo& addWheel( const btVector3& connectionPointCS0, const btVector3& wheelDirectionCS0,const btVector3& wheelAxleCS,btScalar suspensionRestLength,btScalar wheelRadius,const btVehicleTuning& tuning, bool isFrontWheel);
|
||||
|
||||
inline int GetNumWheels() const {
|
||||
inline int getNumWheels() const {
|
||||
return m_wheelInfo.size();
|
||||
}
|
||||
|
||||
std::vector<btWheelInfo> m_wheelInfo;
|
||||
|
||||
|
||||
const btWheelInfo& GetWheelInfo(int index) const;
|
||||
const btWheelInfo& getWheelInfo(int index) const;
|
||||
|
||||
btWheelInfo& GetWheelInfo(int index);
|
||||
btWheelInfo& getWheelInfo(int index);
|
||||
|
||||
void UpdateWheelTransformsWS(btWheelInfo& wheel );
|
||||
void updateWheelTransformsWS(btWheelInfo& wheel );
|
||||
|
||||
|
||||
void SetBrake(float brake,int wheelIndex);
|
||||
void setBrake(float brake,int wheelIndex);
|
||||
|
||||
void SetPitchControl(float pitch)
|
||||
void setPitchControl(float pitch)
|
||||
{
|
||||
m_pitchControl = pitch;
|
||||
}
|
||||
|
||||
void UpdateSuspension(btScalar deltaTime);
|
||||
void updateSuspension(btScalar deltaTime);
|
||||
|
||||
void UpdateFriction(btScalar timeStep);
|
||||
void updateFriction(btScalar timeStep);
|
||||
|
||||
|
||||
|
||||
inline btRigidBody* GetRigidBody()
|
||||
inline btRigidBody* getRigidBody()
|
||||
{
|
||||
return m_chassisBody;
|
||||
}
|
||||
|
||||
const btRigidBody* GetRigidBody() const
|
||||
const btRigidBody* getRigidBody() const
|
||||
{
|
||||
return m_chassisBody;
|
||||
}
|
||||
|
||||
inline int GetRightAxis() const
|
||||
inline int getRightAxis() const
|
||||
{
|
||||
return m_indexRightAxis;
|
||||
}
|
||||
inline int GetUpAxis() const
|
||||
inline int getUpAxis() const
|
||||
{
|
||||
return m_indexUpAxis;
|
||||
}
|
||||
|
||||
inline int GetForwardAxis() const
|
||||
inline int getForwardAxis() const
|
||||
{
|
||||
return m_indexForwardAxis;
|
||||
}
|
||||
|
||||
virtual void SetCoordinateSystem(int rightIndex,int upIndex,int forwardIndex)
|
||||
virtual void setCoordinateSystem(int rightIndex,int upIndex,int forwardIndex)
|
||||
{
|
||||
m_indexRightAxis = rightIndex;
|
||||
m_indexUpAxis = upIndex;
|
||||
m_indexForwardAxis = forwardIndex;
|
||||
}
|
||||
|
||||
virtual void BuildJacobian()
|
||||
virtual void buildJacobian()
|
||||
{
|
||||
//not yet
|
||||
}
|
||||
|
||||
virtual void SolveConstraint(btScalar timeStep)
|
||||
virtual void solveConstraint(btScalar timeStep)
|
||||
{
|
||||
//not yet
|
||||
}
|
||||
|
||||
@@ -27,7 +27,7 @@ virtual ~btVehicleRaycaster()
|
||||
btScalar m_distFraction;
|
||||
};
|
||||
|
||||
virtual void* CastRay(const btVector3& from,const btVector3& to, btVehicleRaycasterResult& result) = 0;
|
||||
virtual void* castRay(const btVector3& from,const btVector3& to, btVehicleRaycasterResult& result) = 0;
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -12,14 +12,14 @@
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h" // for pointvelocity
|
||||
|
||||
|
||||
btScalar btWheelInfo::GetSuspensionRestLength() const
|
||||
btScalar btWheelInfo::getSuspensionRestLength() const
|
||||
{
|
||||
|
||||
return m_suspensionRestLength1;
|
||||
|
||||
}
|
||||
|
||||
void btWheelInfo::UpdateWheel(const btRigidBody& chassis,RaycastInfo& raycastInfo)
|
||||
void btWheelInfo::updateWheel(const btRigidBody& chassis,RaycastInfo& raycastInfo)
|
||||
{
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@ void btWheelInfo::UpdateWheel(const btRigidBody& chassis,RaycastInfo& raycastInf
|
||||
|
||||
else // Not in contact : position wheel in a nice (rest length) position
|
||||
{
|
||||
m_raycastInfo.m_suspensionLength = this->GetSuspensionRestLength();
|
||||
m_raycastInfo.m_suspensionLength = this->getSuspensionRestLength();
|
||||
m_suspensionRelativeVelocity = 0.0f;
|
||||
m_raycastInfo.m_contactNormalWS = -m_raycastInfo.m_wheelDirectionWS;
|
||||
m_clippedInvContactDotSuspension = 1.0f;
|
||||
|
||||
@@ -58,7 +58,7 @@ struct btWheelInfo
|
||||
btVector3 m_wheelAxleCS; // const or modified by steering
|
||||
btScalar m_suspensionRestLength1;//const
|
||||
btScalar m_maxSuspensionTravelCm;
|
||||
btScalar GetSuspensionRestLength() const;
|
||||
btScalar getSuspensionRestLength() const;
|
||||
btScalar m_wheelsRadius;//const
|
||||
btScalar m_suspensionStiffness;//const
|
||||
btScalar m_wheelsDampingCompression;//const
|
||||
@@ -102,7 +102,7 @@ struct btWheelInfo
|
||||
|
||||
}
|
||||
|
||||
void UpdateWheel(const btRigidBody& chassis,RaycastInfo& raycastInfo);
|
||||
void updateWheel(const btRigidBody& chassis,RaycastInfo& raycastInfo);
|
||||
|
||||
btScalar m_clippedInvContactDotSuspension;
|
||||
btScalar m_suspensionRelativeVelocity;
|
||||
|
||||
Reference in New Issue
Block a user