How to eliminate slippage when grasping soft objects with Flex backend?

Hi NVIDIA and fellow robotics friends,

I’m a PhD student currently working on deformable object grasping. I am trying to enable my surgical robot to grasp soft objects in Issac Gym. However, my objects keep slipping away from my robot’s gripper when the robot attempts to grasp them, as shown in the videos below.
da Vinci slips in Issac Gym 2 (1.5 MB) da Vinci slips in Issac Gym 1 (2.0 MB) da Vinci slips in Issac Gym (1.9 MB)

Over the past 3 days, I have tried tuning many parameters such as friction, thickness, Young, Poisson, etc., but unfortunately, none of those works. I already set both dynamic_friction and static_friction to 100 but nothing improved.

Please give me some advice on how to eliminate slippage in Issac Gym Flex. What parameters of the environment, the robot, and the soft object should I change to enable a robust grasp of the soft bodies?

You can reproduce my situation by running the test_move_joints_independently_and_soft.py file in the Github repo I attach below.
https://github.com/baotruyenthach/dvrk_IssacGym/blob/master/python/examples/test_move_joints_independently_and_soft.py

For your convenience, here are the parameters I’m using:
image
image

Thanks a lot for your help,
Bradley

Hi Bradley,

This scenario is a little challenging due to the scale. I wonder, are you using the gripper visual mesh for collision detection? It is quite complex which will lead to a lot of redundant contacts making the problem harder. If possible you should use a simplified mesh for the rigid body collision shape.

In this case linear (inner) iterations may be more important than substeps. This is because we use triangle mesh-based contact, and once interpenetration occurs it cannot be recovered from. This means each substep needs to be solved to convergence. I would try some solver params in this range:

sim_params.flex.substeps = 4
sim_params.flex.num_outer_iterations = 6
sim_params.flex.num_inner_iterations = 40
sim_params.flex.relaxation = 0.7

Also, ensure you have enough thickness on the shapes to avoid interpenetration.

Hope that helps.

Cheers,
Miles

Hi @milesmacklin ,

Thanks for your quick reply!

I had already tried increasing the num_inner_iterations before but it didn’t really help. From your experience, what do you think is the main cause of slippage? When making contact with my robot’s gripper, the soft object doesn’t stick to the gripper at all (please refer to my videos above). Would there be any parameters of the object/actor to increase this “stickiness”?

Thanks a lot,
Bradley

Hi Bradley,

The main reason for slip in this case would be residual error in the solver, i.e.: failure to converge. This can be due to a number of reasons such as not enough outer/inner iterations, overly complicated contact geometry (too many contacts), bad mass ratios, etc.

You can also try visualizing the contact points using draw_env_soft_contacts, I suspect that the collision meshes you are using are generating too many contacts.

Another potential issue is that it seems the gripper force may be too strong for the material, it seems that it can crush the object quite easily. I would check that the actuator limits and material parameters are realistic.

Hope that helps.

Cheers,
Miles

Hi @milesmacklin,

Thanks for your answer.

I agree that using the gripper visual mesh for collision detection will lead to a lot of redundant contacts making the problem harder. Could you please recommend a good way to simplify the mesh? Which software/techniques should I use?

Kindest regards,
Bradley

Bradley,

You can use https://www.meshlab.net/ to reduce the number of faces/triangles in your model, but you might have to play a lot with the parameters to get the resolution right.

In ROS the recommended approach is to build your own collision model around the visual model as to get a model with least amount of faces while retaining the structure that is important for your collision. You can read a bit about it here:

  1. sw_urdf_exporter/Tutorials/Organizing SolidWorks Assembly for URDF Exporter - ROS Wiki
  2. https://blogs.solidworks.com/teacher/wp-content/uploads/sites/3/WPI-Robotics-SolidWorks-to-Gazebo.pdf (page 5: Collision vs. Visual Models)

Kind regards,
Lars