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:
@@ -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)
|
||||
|
||||
Reference in New Issue
Block a user