Gazebo | Ignition | Community
Ask Your Question
0

Object slips from gripper fingers when grasping in simulation

asked 2019-04-16 10:00:52 -0600

ASTRE gravatar image

updated 2019-04-20 03:38:37 -0600

Hi every one,

I am really getting frustrated with this problem. I have a Gazebo simulation of a KUKA_KR6R900SIXX with a gripper and an object to grasp. The issue is that every time i try to grasp the object, it slips between the fingers of the gripper. I can see the contacts established in Gazebo (see video) but it is like there is no friction between the object and the gripper fingers. What parameters should i fix to make the cylinder stick the gripper. See video here : Kuka_gripper_Gazebo_Sim

Here is my configuration :

1) The gripper fingers link xacro config :

  <joint
    name="Mors_prismatic1_joint"
    type="prismatic">
    <origin
      xyz="0.0014158 -0.020952 0.0995"
      rpy="1.5708 0 0.5236" />
    <parent
      link="${prefix}tool0" />
    <child
      link="Mors_prismatic1_Link" />
    <axis
      xyz="0 0 1" />
    <limit effort="1000" lower="0.0" upper="0.02" velocity="0.01" />
    <dynamics damping="0.7" />
    <dynamics damping="1" friction="1"/>
  </joint>

  <joint
    name="Mors_prismatic2_joint"
    type="prismatic">
    <origin
      xyz="0.017437 0.011702 0.0995"
      rpy="1.5708 0 2.618" />
    <parent
      link="${prefix}tool0" />
    <child
      link="Mors_prismatic2_Link" />
    <axis
      xyz="0 0 1" />
    <limit effort="1000" lower="0.0" upper="0.02" velocity="0.01" />
    <dynamics damping="0.7" />
    <dynamics damping="1" friction="1"/>
  </joint>

  <joint
    name="Mors_prismatic3_joint"
    type="prismatic">
    <origin
      xyz="-0.018853 0.00925 0.0995"
      rpy="1.5708 0 -1.5708" />
    <parent
      link="${prefix}tool0" />
    <child
      link="Mors_prismatic3_Link" />
    <axis
      xyz="0 0 1" />
    <limit effort="1000" lower="0.0" upper="0.02" velocity="0.01" />
    <dynamics damping="0.7" />
    <dynamics damping="1" friction="1"/>
  </joint>

2)The gripper fingers gazebo xacro config :

  <gazebo reference="Mors_prismatic1_Link">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
    <implicitSpringDamper>1</implicitSpringDamper>
    <kp>100000.0</kp>
    <kd>1.0</kd>
    <mu1>10.0</mu1>
    <mu2>0.1</mu2>
    <fdir1>1 0 0</fdir1>
    <minDepth>0.01</minDepth>
  </gazebo>

  <gazebo reference="Mors_prismatic2_Link">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff> 
    <implicitSpringDamper>1</implicitSpringDamper>
    <kp>100000.0</kp>
    <kd>1.0</kd>
    <mu1>10.0</mu1>
    <mu2>0.1</mu2>
    <fdir1>1 0 0</fdir1>
    <minDepth>0.01</minDepth>
  </gazebo>



  <gazebo reference="Mors_prismatic3_Link">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
    <implicitSpringDamper>1</implicitSpringDamper>
    <kp>100000.0</kp>
    <kd>1.0</kd>
    <mu1>10.0</mu1>
    <mu2>0.1</mu2>
    <fdir1>1 0 0</fdir1>
    <minDepth>0.01</minDepth>
  </gazebo>

3)The object (cylinder) urdf :

<?xml version="1.0"?>
<robot
  name="Cylinder">
  <link
    name="cylinder_link">
    <inertial>
      <origin
        xyz="-2.27623991509391E-49 1.09168197518227E-17 0.0125"
        rpy="0 0 0" />
      <mass
        value="0.12556160438235" />
      <inertia
        ixx="0"
        ixy="0"
        ixz="0"
        iyy="0"
        iyz="0"
        izz="0" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Cylinder/meshes/base_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.647058823529412 0.619607843137255 0.588235294117647 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://Cylinder/meshes/base_link.STL" />
      </geometry>
    </collision>
  </link>

  <gazebo reference="cylinder_link">
    <implicitSpringDamper>1</implicitSpringDamper>
    <kp>100000.0</kp>
    <kd>1.0</kd>
    <mu1>10.0</mu1>
    <mu2 ...
(more)
edit retag flag offensive close merge delete

Comments

could you please give a short description what you've updated? Didn't it help to set both friction parameters to higher values? And as far as I saw, you've set fdir in x direction (<fdir1>1 0 0 </fdir1>) rather than in z direction which would be needed in your case (<fdir1>0 0 1</fdir>). And I found something else. Depending on the sdf version, you can set the friction model (at least at version 1.6) look here

steradiant gravatar imagesteradiant ( 2019-04-20 09:42:01 -0600 )edit

hey, did you try the Jennifer's grasp plugin?

pmuthu2s gravatar imagepmuthu2s ( 2019-04-23 06:49:17 -0600 )edit

The Jennifer's grasp pluginis what worked for me. A link for my simulation can be found in here : https://github.com/Meguenani/kuka_kr6...

ASTRE gravatar imageASTRE ( 2019-12-10 17:02:44 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2020-04-11 07:12:13 -0600

Annoyingly, it's not just the grippers joints that matter, your robot's joints must also be effort controllers.

edit flag offensive delete link more
0

answered 2019-04-17 05:33:59 -0600

steradiant gravatar image

updated 2019-04-19 08:48:17 -0600

Try to also set <mu2> to a higher value. As you had already noticed, I ran in the same issue as you here. Like explained in my post, I think that the description is very misleading because I made some tests and the values seem to make much more sens if they were forces rather than friction coefficients. Furthermore, one would need to know which direction 1 (first friction direction) and with one is direction 2 (second friction direction) as explained here

In my task I did the same try, I lifted a tube in z-direction. I did some further tests a few moments ago and it seems, that for such a task, you need to set <mu2> to a higher value rather than <mu1>. In my case, I kept both values high to make the gripping also robust against tilting actions.

You can also add the <fdir1> tag to specify the first friction direction.

To answer that exactly, one would have to know in much more detail, how Gazebo implements the ODE

And make sure to increase the value for the links and for the object to grip.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-04-16 10:00:52 -0600

Seen: 4,944 times

Last updated: Apr 11 '20