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:
erwin coumans
2016-09-28 11:17:11 -07:00
parent cf046093ab
commit b81eb79ef5
8 changed files with 63 additions and 21 deletions

View File

@@ -30,6 +30,7 @@ protected:
btScalar m_kd;
btScalar m_kp;
btScalar m_erp;
btScalar m_rhsClamp;//maximum error
public:
@@ -66,7 +67,10 @@ public:
{
return m_erp;
}
virtual void setRhsClamp(btScalar rhsClamp)
{
m_rhsClamp = rhsClamp;
}
virtual void debugDraw(class btIDebugDraw* drawer)
{
//todo(erwincoumans)