Gazebo | Ignition | Community
Ask Your Question
0

Gazebo11 DART Sticking Problem

asked 2020-12-11 09:20:51 -0500

awck gravatar image

updated 2020-12-11 09:26:05 -0500

Dear Gazebo Community,

I am running into a weird "sticking" problem when simulating grasping with DART 6 and Gazebo 11. The problem is that upon collision sometimes contact forces get really high and the grasped object gets "stuck" inside the finger. I made this video that shows the problem: https://youtu.be/-S55gZ7fCl8

Observations:

  • happens less when I grasp spheres
  • happens more when I grasp cylinders or boxes
  • the longer the contact the higher the chance of running into the "sticking problem"
  • happens more when forces are unbalanced (i.e. when I contact object with only 1 finger instead of 3 finger grasp with fingers on opposite sides)
  • when I replaced the collision meshes of the fingers with spheres (and hence only had sphere-sphere contact) the problem also persisted. So I think the meshes of the robotic hand I am using aren't causing the problem.

Solution ideas:

  • I think the key point is that the collision surfaces are smaller for sphere contact than for cylinder or box contact. The Gazebo integration of the DART physics engine currently doesn't allow to specify a max_contacts parameter for the collision. I think the DART engine then goes for the default max. number of contacts (which is 1000 as specified here). If it really allows 1000 contacts then my hypothesis would be that the interaction between the contacts gets messy and leads the simulation to fail.
  • Another problem might be that the contact forces are simply too large. As many other users have found, DART isn't as nicely integrated into Gazebo and so setting collision/material parameters isn't as easy as simply specifying it in the SDF. I think an idea might be to change the <restitution_coefficient>, because as I understand it uses the DART default (which is 0 as specified here, meaning 100% inelastic collisions). Could this be the solution? In contrast, the ODE engine offers stiffness and damping material parameters that can be tuned to make the simulation more stable, but as I understand DART doesn't have these parameters as it uses a hard contact model, correct?
  • Another idea might be to use DART SoftBodyNodes but by this hasn't been properly integrated into Gazebo11 yet, as this issue suggests. As of now I am using the standard BodyNodes, which are simulating rigid body contact, as I understand.

Any comments are much appreciated. I think some guidance before implementing any of the solution ideas would be good. Maybe I'm missing something obvious.

Thanks, Alex

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-03-02 15:48:48 -0500

awck gravatar image

This seems to be a problem with the FCL collision detection that converts primitives to meshes (see this issue). If you set the collision detection to Bullet, the problem is solved!

Put this in your world file:

<physics type="dart">
  <dart>
    <collision_detector>bullet</collision_detector>
  </dart>
</physics>
edit flag offensive delete link more
Login/Signup to Answer

Question Tools

2 followers

Stats

Asked: 2020-12-11 09:20:51 -0500

Seen: 215 times

Last updated: Mar 02 '21