ping-pong back/forward in PGS solving iterations to reduce bias in constraint order
add experimental rhs clamp in btMultiBodyJointMotor to control maximum error resolution.
This commit is contained in:
@@ -31,9 +31,12 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
|
||||
//solve featherstone non-contact constraints
|
||||
|
||||
//printf("m_multiBodyNonContactConstraints = %d\n",m_multiBodyNonContactConstraints.size());
|
||||
|
||||
for (int j=0;j<m_multiBodyNonContactConstraints.size();j++)
|
||||
{
|
||||
btMultiBodySolverConstraint& constraint = m_multiBodyNonContactConstraints[j];
|
||||
int index = iteration&1? j : m_multiBodyNonContactConstraints.size()-1-j;
|
||||
|
||||
btMultiBodySolverConstraint& constraint = m_multiBodyNonContactConstraints[index];
|
||||
|
||||
resolveSingleConstraintRowGeneric(constraint);
|
||||
if(constraint.m_multiBodyA)
|
||||
|
||||
Reference in New Issue
Block a user