Default simulation parameters do not facilitate simple grips

Discussion in 'HAPTIX' started by David Kluger, Nov 3, 2015.

  1. I am looking for some parameter suggestions for a very simple task: pick up a small 2.5" cube with a two-finger pinch grip. Once the parameters are changed to make this simple grip possible, my hope is handling objects in the simulation will be much easier with other more complicated gripping patterns.

    Pinch grips do not perform well in MuJoCo with the default hand. The cube can be pinched, but once the hand is raised, the block slides out of the fingers. This is not a function of the block being too heavy, since I tried making the block 1/100th of the default density to no avail. I also raised tangential friction, no luck. I tried messing with the new solver parameters (also to no avail), but I am having trouble understanding how solref and solimp affect everything from object stiffness/compliance to contact interactions. I appreciate the effort to improve the documentation here, but it is still way over my head. I have a gut feeling that the underlying parameters that can improve a pinch grip are somewhere in here, but I do not know how to change them.

    Please reply with any suggestions, not just those limited to solref and solimp mods.
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    It is hard to say without playing with the specific model. 2.5" is not that small; in some of our VR demos we grasp similar sized objects with the default MPL hand controlled via a CyberGlove. So I wonder if this is a matter of control rather than modelling and simulation...

    How exactly is the cube sliding out? Does it happen gradually or immediately? Is it because of twisting - which can be caused by the fingers not pushing against other? Is the contact force too small - which can happen if you are just touching the surface but not really squeezing? One test you could perform is disable gravity (from the Option dialog) and then try to grasp and move/shake the cube.

    To get a better intuition of that the contact solver parameters do, you can override them from the Option dialog at runtime and experiment with different settings quickly. Other than solref, solimp and friction, there is the contact margin that determines when contacts are first detected, and also the actual contact force you are applying. I am assuming you have torsional friction enabled, with condim=4? This is very helpful for stabilizing a grasp.

    We are currently fine-tuning the new Luke hand model; maybe we should include a cube-lifting demo performed by an automatic controller.
     
  3. I've seen the video of you manipulating these objects in MuJoCo with a CyberGlove. The key difference is we want to pick things up with a pinch grip and not have them slide out, not fully encompass an object with a power grip/fist grip to pick it up. These, in my opinion, are two fundamentally different problems. The power grip works fine, the pinch grip does not.

    Gradually, over the course of roughly 3 seconds. We don't want to disable gravity for our tests because this greatly sacrifices the realism MuJoCo provides. I can disable it for the purpose of testing the pinch grip though and get back to you.

    I do. We were previously messing with tangential friction to make this task easier. I'll start messing with the torsional parameter to see if that helps.

    I have attached the files for the simple 2.5" cube model so you guys can experiment if you so choose. I've also attached two pictures showing the problem we are encountering. The "start" image shows the grip applying a pretty strong compressing force on the block. The contact on the block was ~0.4318^3 (units?; from using contact = mj_get_contact(); contact.force). Right after this force was applied, I lifted the hand, and the block falls right out ("end" image).
     

    Attached Files:

    Ethan Brooks likes this.
  4. The block no longer slides towards the floor since there is 0 gravity, but the pinching force very slowly squeezes the block out from between the fingers. This is due to, I assume, slight shear forces being applied that move the block out of the grip which torsional/tangential friction cannot prevent.

    In a nutshell, I am looking for parameters that will prevent a loss of grip due to shear forces. Think of it as making contact interactions more sticky.
     
  5. Emo Todorov

    Emo Todorov Administrator Staff Member

    How about using harder contact settings, for example solimp="0.95 0.95 0.01". Actually this reminds me that Yuval Tassa (now at DeepMind) mentioned something related; they had to use harder contact settings for grasping.

    Smaller values of solimp add a larger regularizer to the optimization problem over constraint forces. As a result, the solver may pick contact forces that are too small and do not go all the way to the boundary of the friction cone.

    If the object is slipping out of the grip rather than twisting, the problem is not the lack of torsional friction.

    Disabling gravity is just a diagnostic. In particular, if you can shake the object and it doesn't fly away, this would mean that the issue is with contact forces pulling the object over an extended period of time (3 seconds is pretty long; in the real world things slip faster).

    I adjusted the current defaults based on throwing humanoids around, playing with box stacking, and some power grasping. So it is quite possible that the default settings are not suitable for pinch grasping.
     
  6. This definitely helped, but the object still slips out. We want the object to remain stable within the grip. This is because robotic limbs, with soft silicone fingertips, can perform this task easily. We want to emulate this performance within the VRE.

    Any other suggestions?
     
  7. Emo Todorov

    Emo Todorov Administrator Staff Member

    I would have to play with it myself to improve it further. You can try solimp="0.99 0.99 0.01". You can also try solref="0.01 1". Reducing the first number (which is the recovery time constant) also has the effect of making contacts harder, albeit in a different way. Making tangential friction larger can also help, unless it is already large (say around 1.5).

    In general, harder contacts can make simulations unstable, so if that happens reduce the time constant a bit. Although the above parameters should work with the default time step.
     
  8. Emo Todorov

    Emo Todorov Administrator Staff Member

    One more idea: can you try the elliptic solver instead of the default PGS solver? The elliptic solver handles the friction cone more accurately. You can change it from the Option dialog.
     
  9. Yes! This works waayyyyy better than before! Params of interest: all geom condim="4", solimp="0.99 0.99 0.01", solref="0.01 1", and solver="elliptic". The block can now be suspended for ~100 seconds without slipping out of the grip and I do not see any unstable simulation behavior (in this very simple world). I didn't change any friction coefficients. I will have to play around in more complicated environments to see if these adjustments have adverse effects on simulation behavior. I'll get back to you about how these changes affect performance in the VRE once we have a patient controlling the limb with these new geom parameters. Thanks!
     
  10. Emo Todorov

    Emo Todorov Administrator Staff Member

    Good to hear! If you keep the rest of the settings but use PGS, does the behavior get worse? The reason I ask is because the elliptic solver (like PGS) uses dense matrices internally - which is slow in simulations with large number of floating objects. The only viable solver in that case is the sparse solver, but it only works with pyramid approximations to the friction cone, like PGS. In other words, we don't have an analog of the elliptic solver that can exploit sparsity in large systems.
     
  11. Hello,

    I was hoping to get some help with a similar problem. I am training a simulated UR5 robot to learn to carry an object (so far simple cylinders, boxes). Often, however, the object will slip out, particularly when the robot rotates its gripper. I was hoping to get some suggestions for parameter changes that would produce a stickier grip between the gripper and object. I have tried the parameter changes recommended in this thread including geom condim, solimp, solref, and friction cone and have also increased the no slip iterations. These changes, particularly enabling the no slip solver, have been helpful in reducing slippage but some object slipping remains. I have attached my Mujoco model and associated meshes. I have also included below a link to a video showing the slipping.



    Thank you for the help!
     

    Attached Files:

  12. Looks like I have figured out the bulk of the problem. I had set a default damping setting for all of the joints that was causing the cylinder to resist movement and thus not rotate when the gripper rotated.