diff --git a/src/BulletDynamics/CMakeLists.txt b/src/BulletDynamics/CMakeLists.txt index cc4727639..b98cca6f8 100644 --- a/src/BulletDynamics/CMakeLists.txt +++ b/src/BulletDynamics/CMakeLists.txt @@ -14,6 +14,7 @@ SET(BulletDynamics_SRCS ConstraintSolver/btHingeConstraint.cpp ConstraintSolver/btPoint2PointConstraint.cpp ConstraintSolver/btSequentialImpulseConstraintSolver.cpp + ConstraintSolver/btNNCGConstraintSolver.cpp ConstraintSolver/btSliderConstraint.cpp ConstraintSolver/btSolve2LinearConstraint.cpp ConstraintSolver/btTypedConstraint.cpp @@ -53,6 +54,7 @@ SET(ConstraintSolver_HDRS ConstraintSolver/btJacobianEntry.h ConstraintSolver/btPoint2PointConstraint.h ConstraintSolver/btSequentialImpulseConstraintSolver.h + ConstraintSolver/btNNCGConstraintSolver.h ConstraintSolver/btSliderConstraint.h ConstraintSolver/btSolve2LinearConstraint.h ConstraintSolver/btSolverBody.h diff --git a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h index 1ba1cd1e8..890afe6da 100644 --- a/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h +++ b/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h @@ -33,7 +33,8 @@ class btDispatcher; enum btConstraintSolverType { BT_SEQUENTIAL_IMPULSE_SOLVER=1, - BT_MLCP_SOLVER=2 + BT_MLCP_SOLVER=2, + BT_NNCG_SOLVER=4 }; class btConstraintSolver diff --git a/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp new file mode 100644 index 000000000..11fbadef7 --- /dev/null +++ b/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp @@ -0,0 +1,463 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#include "btNNCGConstraintSolver.h" + + + + + + +btScalar btNNCGConstraintSolver::solveGroupCacheFriendlySetup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer) +{ + btScalar val = btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup( bodies,numBodies,manifoldPtr, numManifolds, constraints,numConstraints,infoGlobal,debugDrawer); + + m_pNC.resizeNoInitialize(m_tmpSolverNonContactConstraintPool.size()); + m_pC.resizeNoInitialize(m_tmpSolverContactConstraintPool.size()); + m_pCF.resizeNoInitialize(m_tmpSolverContactFrictionConstraintPool.size()); + m_pCRF.resizeNoInitialize(m_tmpSolverContactRollingFrictionConstraintPool.size()); + + m_deltafNC.resizeNoInitialize(m_tmpSolverNonContactConstraintPool.size()); + m_deltafC.resizeNoInitialize(m_tmpSolverContactConstraintPool.size()); + m_deltafCF.resizeNoInitialize(m_tmpSolverContactFrictionConstraintPool.size()); + m_deltafCRF.resizeNoInitialize(m_tmpSolverContactRollingFrictionConstraintPool.size()); + + return val; +} + +btScalar btNNCGConstraintSolver::solveSingleIteration(int iteration, btCollisionObject** /*bodies */,int /*numBodies*/,btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* /*debugDrawer*/) +{ + + int numNonContactPool = m_tmpSolverNonContactConstraintPool.size(); + int numConstraintPool = m_tmpSolverContactConstraintPool.size(); + int numFrictionPool = m_tmpSolverContactFrictionConstraintPool.size(); + + if (infoGlobal.m_solverMode & SOLVER_RANDMIZE_ORDER) + { + if (1) // uncomment this for a bit less random ((iteration & 7) == 0) + { + + for (int j=0; j0 ? deltaflengthsqr / m_deltafLengthSqrPrev : 2; + if (beta>1) + { + for (int j=0;jisEnabled()) + { + int bodyAid = getOrInitSolverBody(constraints[j]->getRigidBodyA(),infoGlobal.m_timeStep); + int bodyBid = getOrInitSolverBody(constraints[j]->getRigidBodyB(),infoGlobal.m_timeStep); + btSolverBody& bodyA = m_tmpSolverBodyPool[bodyAid]; + btSolverBody& bodyB = m_tmpSolverBodyPool[bodyBid]; + constraints[j]->solveConstraintObsolete(bodyA,bodyB,infoGlobal.m_timeStep); + } + } + + ///solve all contact constraints using SIMD, if available + if (infoGlobal.m_solverMode & SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS) + { + int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); + int multiplier = (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS)? 2 : 1; + + for (int c=0;cbtScalar(0)) + { + solveManifold.m_lowerLimit = -(solveManifold.m_friction*totalImpulse); + solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; + btScalar deltaf = resolveSingleConstraintRowGenericSIMD(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); + m_deltafCF[c*multiplier] = deltaf; + deltaflengthsqr += deltaf*deltaf; + } else { + m_deltafCF[c*multiplier] = 0; + } + } + + if (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS) + { + + btSolverConstraint& solveManifold = m_tmpSolverContactFrictionConstraintPool[m_orderFrictionConstraintPool[c*multiplier+1]]; + + if (totalImpulse>btScalar(0)) + { + solveManifold.m_lowerLimit = -(solveManifold.m_friction*totalImpulse); + solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; + btScalar deltaf = resolveSingleConstraintRowGenericSIMD(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); + m_deltafCF[c*multiplier+1] = deltaf; + deltaflengthsqr += deltaf*deltaf; + } else { + m_deltafCF[c*multiplier+1] = 0; + } + } + } + } + + } + else//SOLVER_INTERLEAVE_CONTACT_AND_FRICTION_CONSTRAINTS + { + //solve the friction constraints after all contact constraints, don't interleave them + int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); + int j; + + for (j=0;jbtScalar(0)) + { + solveManifold.m_lowerLimit = -(solveManifold.m_friction*totalImpulse); + solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; + + //resolveSingleConstraintRowGenericSIMD(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); + btScalar deltaf = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); + m_deltafCF[j] = deltaf; + deltaflengthsqr += deltaf*deltaf; + } else { + m_deltafCF[j] = 0; + } + } + + + int numRollingFrictionPoolConstraints = m_tmpSolverContactRollingFrictionConstraintPool.size(); + for (j=0;jbtScalar(0)) + { + btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse; + if (rollingFrictionMagnitude>rollingFrictionConstraint.m_friction) + rollingFrictionMagnitude = rollingFrictionConstraint.m_friction; + + rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude; + rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude; + + btScalar deltaf = resolveSingleConstraintRowGenericSIMD(m_tmpSolverBodyPool[rollingFrictionConstraint.m_solverBodyIdA],m_tmpSolverBodyPool[rollingFrictionConstraint.m_solverBodyIdB],rollingFrictionConstraint); + m_deltafCRF[j] = deltaf; + deltaflengthsqr += deltaf*deltaf; + } else { + m_deltafCRF[j] = 0; + } + } + + + } + } + + + + } else + { + + if (iteration< infoGlobal.m_numIterations) + { + for (int j=0;jisEnabled()) + { + int bodyAid = getOrInitSolverBody(constraints[j]->getRigidBodyA(),infoGlobal.m_timeStep); + int bodyBid = getOrInitSolverBody(constraints[j]->getRigidBodyB(),infoGlobal.m_timeStep); + btSolverBody& bodyA = m_tmpSolverBodyPool[bodyAid]; + btSolverBody& bodyB = m_tmpSolverBodyPool[bodyBid]; + constraints[j]->solveConstraintObsolete(bodyA,bodyB,infoGlobal.m_timeStep); + } + } + ///solve all contact constraints + int numPoolConstraints = m_tmpSolverContactConstraintPool.size(); + for (int j=0;jbtScalar(0)) + { + solveManifold.m_lowerLimit = -(solveManifold.m_friction*totalImpulse); + solveManifold.m_upperLimit = solveManifold.m_friction*totalImpulse; + + btScalar deltaf = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[solveManifold.m_solverBodyIdA],m_tmpSolverBodyPool[solveManifold.m_solverBodyIdB],solveManifold); + m_deltafCF[j] = deltaf; + deltaflengthsqr += deltaf*deltaf; + } else { + m_deltafCF[j] = 0; + } + } + + int numRollingFrictionPoolConstraints = m_tmpSolverContactRollingFrictionConstraintPool.size(); + for (int j=0;jbtScalar(0)) + { + btScalar rollingFrictionMagnitude = rollingFrictionConstraint.m_friction*totalImpulse; + if (rollingFrictionMagnitude>rollingFrictionConstraint.m_friction) + rollingFrictionMagnitude = rollingFrictionConstraint.m_friction; + + rollingFrictionConstraint.m_lowerLimit = -rollingFrictionMagnitude; + rollingFrictionConstraint.m_upperLimit = rollingFrictionMagnitude; + + btScalar deltaf = resolveSingleConstraintRowGeneric(m_tmpSolverBodyPool[rollingFrictionConstraint.m_solverBodyIdA],m_tmpSolverBodyPool[rollingFrictionConstraint.m_solverBodyIdB],rollingFrictionConstraint); + m_deltafCRF[j] = deltaf; + deltaflengthsqr += deltaf*deltaf; + } else { + m_deltafCRF[j] = 0; + } + } + } + } + + + + + if (!m_onlyForNoneContact) + { + if (iteration==0) + { + for (int j=0;j0 ? deltaflengthsqr / m_deltafLengthSqrPrev : 2; + if (beta>1) { + for (int j=0;j m_pNC; // p for None Contact constraints + btAlignedObjectArray m_pC; // p for Contact constraints + btAlignedObjectArray m_pCF; // p for ContactFriction constraints + btAlignedObjectArray m_pCRF; // p for ContactRollingFriction constraints + + //These are recalculated in every iterations. We just keep these to prevent reallocation in each iteration. + btAlignedObjectArray m_deltafNC; // deltaf for NoneContact constraints + btAlignedObjectArray m_deltafC; // deltaf for Contact constraints + btAlignedObjectArray m_deltafCF; // deltaf for ContactFriction constraints + btAlignedObjectArray m_deltafCRF; // deltaf for ContactRollingFriction constraints + + +protected: + + virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject** bodies,int numBodies,const btContactSolverInfo& infoGlobal); + virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer); + + virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer); + +public: + + BT_DECLARE_ALIGNED_ALLOCATOR(); + + btNNCGConstraintSolver() : btSequentialImpulseConstraintSolver(), m_onlyForNoneContact(false) {} + + virtual btConstraintSolverType getSolverType() const + { + return BT_NNCG_SOLVER; + } + + bool m_onlyForNoneContact; +}; + + + + +#endif //BT_NNCG_CONSTRAINT_SOLVER_H + diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index 4b1155940..aabfa208d 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -58,7 +58,7 @@ static inline __m128 btSimdDot3( __m128 vec0, __m128 vec1 ) #endif//USE_SIMD // Project Gauss Seidel or the equivalent Sequential Impulse -void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) +btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { #ifdef USE_SIMD __m128 cpAppliedImp = _mm_set1_ps(c.m_appliedImpulse); @@ -86,13 +86,14 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD( body1.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body1.internalGetDeltaAngularVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentA.mVec128,impulseMagnitude)); body2.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaLinearVelocity().mVec128,_mm_mul_ps(linearComponentB,impulseMagnitude)); body2.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaAngularVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentB.mVec128,impulseMagnitude)); + return deltaImpulse.m128_f32[0]; #else - resolveSingleConstraintRowGeneric(body1,body2,c); + return resolveSingleConstraintRowGeneric(body1,body2,c); #endif } // Project Gauss Seidel or the equivalent Sequential Impulse - void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGeneric(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) +btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGeneric(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { btScalar deltaImpulse = c.m_rhs-btScalar(c.m_appliedImpulse)*c.m_cfm; const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(body1.internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(body1.internalGetDeltaAngularVelocity()); @@ -120,9 +121,11 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD( body1.internalApplyImpulse(c.m_contactNormal1*body1.internalGetInvMass(),c.m_angularComponentA,deltaImpulse); body2.internalApplyImpulse(c.m_contactNormal2*body2.internalGetInvMass(),c.m_angularComponentB,deltaImpulse); + + return deltaImpulse; } - void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimitSIMD(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) +btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimitSIMD(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { #ifdef USE_SIMD __m128 cpAppliedImp = _mm_set1_ps(c.m_appliedImpulse); @@ -147,13 +150,14 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD( body1.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body1.internalGetDeltaAngularVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentA.mVec128,impulseMagnitude)); body2.internalGetDeltaLinearVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaLinearVelocity().mVec128,_mm_mul_ps(linearComponentB,impulseMagnitude)); body2.internalGetDeltaAngularVelocity().mVec128 = _mm_add_ps(body2.internalGetDeltaAngularVelocity().mVec128 ,_mm_mul_ps(c.m_angularComponentB.mVec128,impulseMagnitude)); + return deltaImpulse.m128_f32[0]; #else - resolveSingleConstraintRowLowerLimit(body1,body2,c); + return resolveSingleConstraintRowLowerLimit(body1,body2,c); #endif } -// Projected Gauss Seidel or the equivalent Sequential Impulse - void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimit(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) + +btScalar btSequentialImpulseConstraintSolver::resolveSingleConstraintRowLowerLimit(btSolverBody& body1,btSolverBody& body2,const btSolverConstraint& c) { btScalar deltaImpulse = c.m_rhs-btScalar(c.m_appliedImpulse)*c.m_cfm; const btScalar deltaVel1Dotn = c.m_contactNormal1.dot(body1.internalGetDeltaLinearVelocity()) + c.m_relpos1CrossNormal.dot(body1.internalGetDeltaAngularVelocity()); @@ -173,6 +177,8 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD( } body1.internalApplyImpulse(c.m_contactNormal1*body1.internalGetInvMass(),c.m_angularComponentA,deltaImpulse); body2.internalApplyImpulse(c.m_contactNormal2*body2.internalGetInvMass(),c.m_angularComponentB,deltaImpulse); + + return deltaImpulse; } @@ -430,6 +436,7 @@ void btSequentialImpulseConstraintSolver::setupFrictionConstraint(btSolverConstr btSimdScalar velocityError = desiredVelocity - rel_vel; btSimdScalar velocityImpulse = velocityError * btSimdScalar(solverConstraint.m_jacDiagABInv); solverConstraint.m_rhs = velocityImpulse; + solverConstraint.m_rhsPenetration = 0.f; solverConstraint.m_cfm = cfmSlip; solverConstraint.m_lowerLimit = -solverConstraint.m_friction; solverConstraint.m_upperLimit = solverConstraint.m_friction; @@ -1452,8 +1459,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration for (j=0;j& limitDependency, int numIterations, bool useSparsity = true) { + + if (m_useLoHighBounds) + { + + BT_PROFILE("btLemkeSolver::solveMLCP"); int n = A.rows(); if (0==n) return true; -// printf("================ solving using Lemke/Newton/Fixpoint\n"); + bool fail = false; + btVectorXu solution(n); btVectorXu q1; q1.resize(n); for (int row=0;row100000) + if (x[i]>m_maxValue) { if (x[i]> errorValueMax) { @@ -223,7 +234,86 @@ public: } ////printf("x[i] = %f,",x[i]); } - if (x[i]<-10000) + if (x[i]<-m_maxValue) + { + if (x[i]m_maxValue) + { + if (x[i]> errorValueMax) + { + fail = true; + errorIndexMax = i; + errorValueMax = x[i]; + } + ////printf("x[i] = %f,",x[i]); + } + if (x[i]<-m_maxValue) { if (x[i]& limitDependency, int numIterations, bool useSparsity = true) { + if (!A.rows()) + return true; + //the A matrix is sparse, so compute the non-zero elements + A.rowComputeNonZeroElements(); + //A is a m-n matrix, m rows, n columns btAssert(A.rows() == b.rows()); diff --git a/src/LinearMath/btMatrixX.h b/src/LinearMath/btMatrixX.h index 52cc79b3a..b025da7a1 100644 --- a/src/LinearMath/btMatrixX.h +++ b/src/LinearMath/btMatrixX.h @@ -113,10 +113,13 @@ struct btVectorX } void setZero() { - // for (int i=0;i m_storage; - btAlignedObjectArray< btAlignedObjectArray > m_rowNonZeroElements1; - btAlignedObjectArray< btAlignedObjectArray > m_colNonZeroElements; + mutable btAlignedObjectArray< btAlignedObjectArray > m_rowNonZeroElements1; T* getBufferPointerWritable() { @@ -196,7 +198,6 @@ struct btMatrixX BT_PROFILE("m_storage.resize"); m_storage.resize(rows*cols); } - clearSparseInfo(); } int cols() const { @@ -231,14 +232,6 @@ struct btMatrixX void setElem(int row,int col, T val) { m_setElemOperations++; - if (val) - { - if (m_storage[col+row*m_cols]==0.f) - { - m_rowNonZeroElements1[row].push_back(col); - m_colNonZeroElements[col].push_back(row); - } - } m_storage[row*m_cols+col] = val; } @@ -256,11 +249,10 @@ struct btMatrixX void copyLowerToUpperTriangle() { int count=0; - for (int row=0;row& mat) { for (int j=0;j& mat) //printf("%s ---------------------\n",msg); for (int i=0;i