Merge remote-tracking branch 'remotes/bulletphysics/master'
# Conflicts: # src/BulletCollision/CollisionDispatch/btCollisionWorldImporter.h
This commit is contained in:
@@ -137,8 +137,6 @@ btKinematicCharacterController::btKinematicCharacterController (btPairCachingGho
|
||||
m_ghostObject = ghostObject;
|
||||
m_up.setValue(0.0f, 0.0f, 1.0f);
|
||||
m_jumpAxis.setValue(0.0f, 0.0f, 1.0f);
|
||||
setUp(up);
|
||||
setStepHeight(stepHeight);
|
||||
m_addedMargin = 0.02;
|
||||
m_walkDirection.setValue(0.0,0.0,0.0);
|
||||
m_AngVel.setValue(0.0, 0.0, 0.0);
|
||||
@@ -156,13 +154,16 @@ btKinematicCharacterController::btKinematicCharacterController (btPairCachingGho
|
||||
m_wasOnGround = false;
|
||||
m_wasJumping = false;
|
||||
m_interpolateUp = true;
|
||||
setMaxSlope(btRadians(45.0));
|
||||
m_currentStepOffset = 0.0;
|
||||
m_maxPenetrationDepth = 0.2;
|
||||
full_drop = false;
|
||||
bounce_fix = false;
|
||||
m_linearDamping = btScalar(0.0);
|
||||
m_angularDamping = btScalar(0.0);
|
||||
|
||||
setUp(up);
|
||||
setStepHeight(stepHeight);
|
||||
setMaxSlope(btRadians(45.0));
|
||||
}
|
||||
|
||||
btKinematicCharacterController::~btKinematicCharacterController ()
|
||||
@@ -657,7 +658,7 @@ void btKinematicCharacterController::setLinearVelocity(const btVector3& velocity
|
||||
if (c != 0)
|
||||
{
|
||||
//there is a component in walkdirection for vertical velocity
|
||||
btVector3 upComponent = m_up * (sinf(SIMD_HALF_PI - acosf(c)) * m_walkDirection.length());
|
||||
btVector3 upComponent = m_up * (btSin(SIMD_HALF_PI - btAcos(c)) * m_walkDirection.length());
|
||||
m_walkDirection -= upComponent;
|
||||
m_verticalVelocity = (c < 0.0f ? -1 : 1) * upComponent.length();
|
||||
|
||||
|
||||
@@ -642,7 +642,7 @@ void btConeTwistConstraint::calcAngleInfo2(const btTransform& transA, const btTr
|
||||
btTransform trDeltaAB = trB * trPose * trA.inverse();
|
||||
btQuaternion qDeltaAB = trDeltaAB.getRotation();
|
||||
btVector3 swingAxis = btVector3(qDeltaAB.x(), qDeltaAB.y(), qDeltaAB.z());
|
||||
float swingAxisLen2 = swingAxis.length2();
|
||||
btScalar swingAxisLen2 = swingAxis.length2();
|
||||
if(btFuzzyZero(swingAxisLen2))
|
||||
{
|
||||
return;
|
||||
@@ -903,7 +903,7 @@ btVector3 btConeTwistConstraint::GetPointForAngle(btScalar fAngleInRadians, btSc
|
||||
// a^2 b^2
|
||||
// Do the math and it should be clear.
|
||||
|
||||
float swingLimit = m_swingSpan1; // if xEllipse == 0, just use axis b (1)
|
||||
btScalar swingLimit = m_swingSpan1; // if xEllipse == 0, just use axis b (1)
|
||||
if (fabs(xEllipse) > SIMD_EPSILON)
|
||||
{
|
||||
btScalar surfaceSlope2 = (yEllipse*yEllipse)/(xEllipse*xEllipse);
|
||||
|
||||
@@ -43,10 +43,13 @@ struct btContactSolverInfoData
|
||||
btScalar m_restitution;
|
||||
int m_numIterations;
|
||||
btScalar m_maxErrorReduction;
|
||||
btScalar m_sor;
|
||||
btScalar m_erp;//used as Baumgarte factor
|
||||
btScalar m_erp2;//used in Split Impulse
|
||||
btScalar m_globalCfm;//constraint force mixing
|
||||
btScalar m_sor;//successive over-relaxation term
|
||||
btScalar m_erp;//error reduction for non-contact constraints
|
||||
btScalar m_erp2;//error reduction for contact constraints
|
||||
btScalar m_globalCfm;//constraint force mixing for contacts and non-contacts
|
||||
btScalar m_frictionERP;//error reduction for friction constraints
|
||||
btScalar m_frictionCFM;//constraint force mixing for friction constraints
|
||||
|
||||
int m_splitImpulse;
|
||||
btScalar m_splitImpulsePenetrationThreshold;
|
||||
btScalar m_splitImpulseTurnErp;
|
||||
@@ -79,6 +82,8 @@ struct btContactSolverInfo : public btContactSolverInfoData
|
||||
m_erp = btScalar(0.2);
|
||||
m_erp2 = btScalar(0.2);
|
||||
m_globalCfm = btScalar(0.);
|
||||
m_frictionERP = btScalar(0.2);//positional friction 'anchors' are disabled by default
|
||||
m_frictionCFM = btScalar(0.);
|
||||
m_sor = btScalar(1.);
|
||||
m_splitImpulse = true;
|
||||
m_splitImpulsePenetrationThreshold = -.04f;
|
||||
|
||||
@@ -534,7 +534,7 @@ void btSequentialImpulseConstraintSolver::applyAnisotropicFriction(btCollisionOb
|
||||
|
||||
|
||||
|
||||
void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity, btScalar cfmSlip)
|
||||
void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
|
||||
{
|
||||
|
||||
|
||||
@@ -612,7 +612,17 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr
|
||||
|
||||
btScalar velocityError = desiredVelocity - rel_vel;
|
||||
btScalar velocityImpulse = velocityError * solverConstraint.m_jacDiagABInv;
|
||||
solverConstraint.m_rhs = velocityImpulse;
|
||||
|
||||
btScalar penetrationImpulse = btScalar(0);
|
||||
|
||||
if (cp.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR)
|
||||
{
|
||||
btScalar distance = (cp.getPositionWorldOnA() - cp.getPositionWorldOnB()).dot(normalAxis);
|
||||
btScalar positionalError = -distance * infoGlobal.m_frictionERP/infoGlobal.m_timeStep;
|
||||
penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv;
|
||||
}
|
||||
|
||||
solverConstraint.m_rhs = penetrationImpulse + velocityImpulse;
|
||||
solverConstraint.m_rhsPenetration = 0.f;
|
||||
solverConstraint.m_cfm = cfmSlip;
|
||||
solverConstraint.m_lowerLimit = -solverConstraint.m_friction;
|
||||
@@ -621,12 +631,12 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr
|
||||
}
|
||||
}
|
||||
|
||||
btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity, btScalar cfmSlip)
|
||||
btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
|
||||
{
|
||||
btSolverConstraint& solverConstraint = m_tmpSolverContactFrictionConstraintPool.expandNonInitializing();
|
||||
solverConstraint.m_frictionIndex = frictionIndex;
|
||||
setupFrictionConstraint(solverConstraint, normalAxis, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2,
|
||||
colObj0, colObj1, relaxation, desiredVelocity, cfmSlip);
|
||||
colObj0, colObj1, relaxation, infoGlobal, desiredVelocity, cfmSlip);
|
||||
return solverConstraint;
|
||||
}
|
||||
|
||||
@@ -1168,6 +1178,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
|
||||
///In that case, you can set the target relative motion in each friction direction (cp.m_contactMotion1 and cp.m_contactMotion2)
|
||||
///this will give a conveyor belt effect
|
||||
///
|
||||
|
||||
if (!(infoGlobal.m_solverMode & SOLVER_ENABLE_FRICTION_DIRECTION_CACHING) || !(cp.m_contactPointFlags&BT_CONTACT_FLAG_LATERAL_FRICTION_INITIALIZED))
|
||||
{
|
||||
cp.m_lateralFrictionDir1 = vel - cp.m_normalWorldOnB * rel_vel;
|
||||
@@ -1177,7 +1188,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
|
||||
cp.m_lateralFrictionDir1 *= 1.f/btSqrt(lat_rel_vel);
|
||||
applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation,infoGlobal);
|
||||
|
||||
if((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||
{
|
||||
@@ -1185,7 +1196,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
|
||||
cp.m_lateralFrictionDir2.normalize();//??
|
||||
applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal);
|
||||
}
|
||||
|
||||
} else
|
||||
@@ -1194,13 +1205,13 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
|
||||
|
||||
applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal);
|
||||
|
||||
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||
{
|
||||
applyAnisotropicFriction(colObj0,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir2,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal);
|
||||
}
|
||||
|
||||
|
||||
@@ -1212,10 +1223,10 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
|
||||
|
||||
} else
|
||||
{
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation,cp.m_contactMotion1, cp.m_frictionCFM);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal, cp.m_contactMotion1, cp.m_frictionCFM);
|
||||
|
||||
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, cp.m_contactMotion2, cp.m_frictionCFM);
|
||||
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation, infoGlobal, cp.m_contactMotion2, cp.m_frictionCFM);
|
||||
|
||||
}
|
||||
setFrictionConstraintImpulse( solverConstraint, solverBodyIdA, solverBodyIdB, cp, infoGlobal);
|
||||
@@ -1526,7 +1537,8 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
|
||||
sum += iMJaB.dot(solverConstraint.m_relpos2CrossNormal);
|
||||
btScalar fsum = btFabs(sum);
|
||||
btAssert(fsum > SIMD_EPSILON);
|
||||
solverConstraint.m_jacDiagABInv = fsum>SIMD_EPSILON?btScalar(1.)/sum : 0.f;
|
||||
btScalar sorRelaxation = 1.f;//todo: get from globalInfo?
|
||||
solverConstraint.m_jacDiagABInv = fsum>SIMD_EPSILON?sorRelaxation/sum : 0.f;
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -62,6 +62,7 @@ protected:
|
||||
void setupFrictionConstraint( btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,
|
||||
btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,
|
||||
btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar desiredVelocity=0., btScalar cfmSlip=0.);
|
||||
|
||||
void setupTorsionalFrictionConstraint( btSolverConstraint& solverConstraint, const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,
|
||||
@@ -69,7 +70,7 @@ protected:
|
||||
btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation,
|
||||
btScalar desiredVelocity=0., btScalar cfmSlip=0.);
|
||||
|
||||
btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.);
|
||||
btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.);
|
||||
btSolverConstraint& addTorsionalFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,btScalar torsionalFriction, const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0, btScalar cfmSlip=0.f);
|
||||
|
||||
|
||||
|
||||
@@ -1238,7 +1238,7 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar
|
||||
|
||||
|
||||
|
||||
void btMultiBody::solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, float result[6]) const
|
||||
void btMultiBody::solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, btScalar result[6]) const
|
||||
{
|
||||
int num_links = getNumLinks();
|
||||
///solve I * x = rhs, so the result = invI * rhs
|
||||
|
||||
@@ -616,7 +616,7 @@ private:
|
||||
void operator=(const btMultiBody &); // not implemented
|
||||
|
||||
|
||||
void solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, float result[6]) const;
|
||||
void solveImatrix(const btVector3& rhs_top, const btVector3& rhs_bot, btScalar result[6]) const;
|
||||
void solveImatrix(const btSpatialForceVector &rhs, btSpatialMotionVector &result) const;
|
||||
|
||||
void updateLinksDofOffsets()
|
||||
|
||||
@@ -48,9 +48,11 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
|
||||
}
|
||||
|
||||
//solve featherstone normal contact
|
||||
for (int j=0;j<m_multiBodyNormalContactConstraints.size();j++)
|
||||
for (int j0=0;j0<m_multiBodyNormalContactConstraints.size();j0++)
|
||||
{
|
||||
btMultiBodySolverConstraint& constraint = m_multiBodyNormalContactConstraints[j];
|
||||
int index = j0;//iteration&1? j0 : m_multiBodyNormalContactConstraints.size()-1-j0;
|
||||
|
||||
btMultiBodySolverConstraint& constraint = m_multiBodyNormalContactConstraints[index];
|
||||
btScalar residual = 0.f;
|
||||
|
||||
if (iteration < infoGlobal.m_numIterations)
|
||||
@@ -68,11 +70,13 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
|
||||
|
||||
//solve featherstone frictional contact
|
||||
|
||||
for (int j=0;j<this->m_multiBodyFrictionContactConstraints.size();j++)
|
||||
for (int j1=0;j1<this->m_multiBodyFrictionContactConstraints.size();j1++)
|
||||
{
|
||||
if (iteration < infoGlobal.m_numIterations)
|
||||
{
|
||||
btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[j];
|
||||
int index = j1;//iteration&1? j1 : m_multiBodyFrictionContactConstraints.size()-1-j1;
|
||||
|
||||
btMultiBodySolverConstraint& frictionConstraint = m_multiBodyFrictionContactConstraints[index];
|
||||
btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse;
|
||||
//adjust friction limits here
|
||||
if (totalImpulse>btScalar(0))
|
||||
@@ -240,32 +244,39 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol
|
||||
//cfm = 1 / ( dt * kp + kd )
|
||||
//erp = dt * kp / ( dt * kp + kd )
|
||||
|
||||
btScalar cfm = infoGlobal.m_globalCfm;
|
||||
btScalar erp = infoGlobal.m_erp2;
|
||||
|
||||
if ((cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_CFM) || (cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_ERP))
|
||||
{
|
||||
if (cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_CFM)
|
||||
cfm = cp.m_contactCFM;
|
||||
if (cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_ERP)
|
||||
erp = cp.m_contactERP;
|
||||
} else
|
||||
{
|
||||
if (cp.m_contactPointFlags & BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING)
|
||||
{
|
||||
btScalar denom = ( infoGlobal.m_timeStep * cp.m_combinedContactStiffness1 + cp.m_combinedContactDamping1 );
|
||||
if (denom < SIMD_EPSILON)
|
||||
{
|
||||
denom = SIMD_EPSILON;
|
||||
}
|
||||
cfm = btScalar(1) / denom;
|
||||
erp = (infoGlobal.m_timeStep * cp.m_combinedContactStiffness1) / denom;
|
||||
}
|
||||
}
|
||||
|
||||
cfm *= invTimeStep;
|
||||
btScalar cfm;
|
||||
btScalar erp;
|
||||
if (isFriction)
|
||||
{
|
||||
cfm = infoGlobal.m_frictionCFM;
|
||||
erp = infoGlobal.m_frictionERP;
|
||||
} else
|
||||
{
|
||||
cfm = infoGlobal.m_globalCfm;
|
||||
erp = infoGlobal.m_erp2;
|
||||
|
||||
if ((cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_CFM) || (cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_ERP))
|
||||
{
|
||||
if (cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_CFM)
|
||||
cfm = cp.m_contactCFM;
|
||||
if (cp.m_contactPointFlags&BT_CONTACT_FLAG_HAS_CONTACT_ERP)
|
||||
erp = cp.m_contactERP;
|
||||
} else
|
||||
{
|
||||
if (cp.m_contactPointFlags & BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING)
|
||||
{
|
||||
btScalar denom = ( infoGlobal.m_timeStep * cp.m_combinedContactStiffness1 + cp.m_combinedContactDamping1 );
|
||||
if (denom < SIMD_EPSILON)
|
||||
{
|
||||
denom = SIMD_EPSILON;
|
||||
}
|
||||
cfm = btScalar(1) / denom;
|
||||
erp = (infoGlobal.m_timeStep * cp.m_combinedContactStiffness1) / denom;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
cfm *= invTimeStep;
|
||||
|
||||
if (multiBodyA)
|
||||
{
|
||||
@@ -425,8 +436,19 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol
|
||||
|
||||
|
||||
btScalar restitution = 0.f;
|
||||
btScalar penetration = isFriction? 0 : cp.getDistance()+infoGlobal.m_linearSlop;
|
||||
|
||||
btScalar distance = 0;
|
||||
if (!isFriction)
|
||||
{
|
||||
distance = cp.getDistance()+infoGlobal.m_linearSlop;
|
||||
} else
|
||||
{
|
||||
if (cp.m_contactPointFlags & BT_CONTACT_FLAG_FRICTION_ANCHOR)
|
||||
{
|
||||
distance = (cp.getPositionWorldOnA() - cp.getPositionWorldOnB()).dot(contactNormal);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
btScalar rel_vel = 0.f;
|
||||
int ndofA = 0;
|
||||
int ndofB = 0;
|
||||
@@ -521,15 +543,20 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol
|
||||
|
||||
btScalar positionalError = 0.f;
|
||||
btScalar velocityError = restitution - rel_vel;// * damping; //note for friction restitution is always set to 0 (check above) so it is acutally velocityError = -rel_vel for friction
|
||||
|
||||
if (penetration>0)
|
||||
if (isFriction)
|
||||
{
|
||||
positionalError = 0;
|
||||
velocityError -= penetration / infoGlobal.m_timeStep;
|
||||
|
||||
positionalError = -distance * erp/infoGlobal.m_timeStep;
|
||||
} else
|
||||
{
|
||||
positionalError = -penetration * erp/infoGlobal.m_timeStep;
|
||||
if (distance>0)
|
||||
{
|
||||
positionalError = 0;
|
||||
velocityError -= distance / infoGlobal.m_timeStep;
|
||||
|
||||
} else
|
||||
{
|
||||
positionalError = -distance * erp/infoGlobal.m_timeStep;
|
||||
}
|
||||
}
|
||||
|
||||
btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv;
|
||||
@@ -556,7 +583,7 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol
|
||||
}
|
||||
else
|
||||
{
|
||||
solverConstraint.m_rhs = velocityImpulse;
|
||||
solverConstraint.m_rhs = penetrationImpulse+velocityImpulse;
|
||||
solverConstraint.m_rhsPenetration = 0.f;
|
||||
solverConstraint.m_lowerLimit = -solverConstraint.m_friction;
|
||||
solverConstraint.m_upperLimit = solverConstraint.m_friction;
|
||||
@@ -1024,12 +1051,18 @@ void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold*
|
||||
applyAnisotropicFriction(colObj1,cp.m_lateralFrictionDir1,btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
addMultiBodyFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,colObj0,colObj1, relaxation,infoGlobal);
|
||||
|
||||
if (rollingFriction > 0)
|
||||
if (rollingFriction > 0 )
|
||||
{
|
||||
addMultiBodyTorsionalFrictionConstraint(cp.m_normalWorldOnB,manifold,frictionIndex,cp,cp.m_combinedSpinningFriction, colObj0,colObj1, relaxation,infoGlobal);
|
||||
addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal);
|
||||
addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir2,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal);
|
||||
|
||||
if (cp.m_combinedSpinningFriction>0)
|
||||
{
|
||||
addMultiBodyTorsionalFrictionConstraint(cp.m_normalWorldOnB,manifold,frictionIndex,cp,cp.m_combinedSpinningFriction, colObj0,colObj1, relaxation,infoGlobal);
|
||||
}
|
||||
if (cp.m_combinedRollingFriction>0)
|
||||
{
|
||||
|
||||
addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir1,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal);
|
||||
addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir2,manifold,frictionIndex,cp,cp.m_combinedRollingFriction, colObj0,colObj1, relaxation,infoGlobal);
|
||||
}
|
||||
rollingFriction--;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user