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

@@ -302,7 +302,7 @@
</joint>
<link name='finger_right'>
<pose frame=''>0.062 0 0.145 0 0 1.5708</pose>
<pose frame=''>0.042 0 0.145 0 0 1.5708</pose>
<inertial>
<mass>0.2</mass>
<inertia>
@@ -342,7 +342,7 @@
</joint>
<link name='finger_left'>
<pose frame=''>-0.062 0 0.145 0 0 4.71239</pose>
<pose frame=''>-0.042 0 0.145 0 0 4.71239</pose>
<inertial>
<mass>0.2</mass>
<inertia>