The Gazebo grasp fix plugin - JenniferBuehler/gazebo-pkgs GitHub Wiki

Especially in older Gazebo versions (<2), the robot may display strange behaviour when grasping an object: It may wobble, explode, or fly off into space. This is because the physics engine is not optimized for grasping yet. The plugin provided in the package gazebo_grasp_plugin helps to overcome such issues.

In newer Gazebo versions (>2), the robot may not display strange behaviour any more when grasping, but the object to be grasped may still slip off the robot hand. It may be possible to get the robot to grasp the object still, by adjusting the material properties of object and gripper. The force applied to the object by the robot also plays a role. However this may require quite a bit of fine-tuning of the robot URDF and object properties. If this is not of immediate priority to a project, instead it may be easier to use the Gazebo grasp plugin provided in this package.

How it works

The plugin is inspired by gazebo::physics::Gripper. It fixes an object which is grasped to the robot hand to avoid problems with physics engines and to help the object staying in the robot hand without slipping out.

An object is detected as "grasped" as soon as two opposing forces are applied by the gripper links on an object. The object is then fixed to the palm or hand link. As soon as this criterion does not hold any more (e.g. the gripper opens), the object is detached again.

This plugin has no dependencies on ROS. It can run in the background and automatically attaches all objects grasped by the gripper links (tolerances for the criterion "opposing" can be set in the source code, but it is planned to make this a parameter as well).

The implementation is a model plugin, so you have to load the model plugin from the robot URDF:

<gazebo>
   <plugin name="gazebo_grasp_fix" filename="libgazebo_grasp_fix.so">
        <arm>
           <arm_name>name-of-arm</arm_name>
           <palm_link> hand_link_name  </palm_link>
           <gripper_link> finger_index_link_1 </gripper_link>
           <gripper_link> finger_index_link_2 </gripper_link>
           <gripper_link> ... </gripper_link>
        </arm>
       <forces_angle_tolerance>100</forces_angle_tolerance>
       <update_rate>4</update_rate>
       <grip_count_threshold>4</grip_count_threshold>
       <max_grip_count>8</max_grip_count>
       <release_tolerance>0.005</release_tolerance>
       <disable_collisions_on_attach>false</disable_collisions_on_attach>
       <contact_topic>__default_topic__</contact_topic>
    </plugin>
</gazebo>

Description of the arguments:

  • <arm> contains a collections of specification for each arm which can grasp one object (there may be several <arm> tags):
    • <arm_name> is the name of this arm. Has to be unique.
    • <palm_link> has to be the link to which the finger joints are attached.
    • <gripper_link> tags have to include all link names of the gripper/hand which are used to actively grasp objects (these are the links which determine whether a "grasp" exists according to above described criterion).
  • <update_rate> is the rate at which all contact points are checked against the "gripping criterion". Note that in-between such updates, existing contact points may be collected at a higher rate (the Gazebo world update rate). The update_rate is only the rate at which they are processed, which takes a bit of computation time, and therefore should be lower than the gazebo world update rate.
  • <forces_angle_tolerance> is the tolerance angle (in degrees) between two force vectors to be considered "opposing forces". If the angle is smaller than this, they are not opposing.
  • <grip_count_threshold> is number of times in the update loop (running at update_rate) that an object has to be detected as "gripped" in order to attach the object. Adjust this with the update rate.
  • <max_grip_count> is the maximum number of a counter: At each update iteration (running at update_rate), if the "gripping criterion" is met for an object, a counter for this object is increased. max_grip_count is the maximum number recorded for an object. As soon as the counter goes beyond this number, the counter is stopped. As soon as the "gripping criterion" does not hold any more, the number will start to decrease again, (by 1 each time the object is detected as "not grasped" in an update iteration). So this counter is like a "buffer" which, when it is full, maintains the state, and when it is empty, again, the object is released. This should be at least double of grip_count_threshold.
  • <release_tolerance> is the distance which the gripper links are allowed to move away from the object during* a grasp without the object being detached, even if there are currently no actual contacts on the object. This condition can happen if the fingers "wobble" or move ever so slightly away from the object, and therefore the "gripping criterion" fails in a few subsequent update iterations. This setting is to make the behaviour more stable. Setting this number too high will also lead to the object not being detached even if the grippers have opened up to release it, so use this with care.
  • <disable_collisions_on_attach> can be used for the following: When an object is attached, collisions with it may be disabled, in case the robot still keeps wobbling.
  • <contact_topic> is the gazebo topic of contacts. Should normally be left at __default_topic__.

Important

The link names you specify are not necessarily the ones which are published on /tf, if you are using ROS. They must be the link names used in Gazebo. Gazebo joins chains of fixed links into one, so if you have a chain of several links joined by fixed joints, it will become one single link in Gazebo, and the name may change. To find out which link names you have to put into the <palm_link> and <gripper_link> tags, it is easiest if you just launch your robot in Gazebo, and look up how the links are called on the left-hand side properties window. In the "World" tab, expand "Models" to find your robot, then expand this to see the links of your robot (some joints are listed there as well). You can click on them to highlight them in Gazebo. For example, for the Jaco robot on the table, it looks like this:

The palm link is the link to which the object will be attached, therefore it should be the link before the gripper joints. There should be no other movable joints between the palm link and the gripper joints. While it would still work in terms of attaching the object, if any joints in-between palm link and gripper joints move, the object would move out of the grip.

Grasp tutorials

There is a tutorial in the jaco-arm-pkgs wiki which demonstrates the use of this plugin with the Jaco arm in jaco-arm-pkgs. A similar (more advanced) tutorial can be found in the grasp-execution-pkgs wiki .

⚠️ **GitHub.com Fallback** ⚠️