Robotics StackExchange | Archived questions

Friction between gripper and stone not working properly

Hi there,

I'm using Gazebo to simulate a pick and place of objects with irregular shape like meshes of stones. When picking an object Gazebo does not seem to take the friction between both objects (stone and gripper ) into account.

Here is a quick video of what happens: https://www.dropbox.com/s/8svnza7dze01kz2/Kazam_screencast_00000.mp4?dl=0

The friction coefficients of both objects are:

Stone

<gazebo reference="base_link">
  <mu1 value="1.2"/>
  <mu2 value="1.1"/>
  <kp  value="5000000.0" />
  <kd  value="1.0" />
  <fdir1 value="1 0 0"/>
  <collision>
    <surface>
      <bounce>
        <restitution_coefficient> 0.1 </restitution_coefficient>
        <threshold>0.</threshold>
      </bounce>
      <contact>
        <ode>
          <max_vel>0.1</max_vel>
          <min_depth>0.001</min_depth>
        </ode>
      </contact>
    </surface>
  </collision>
  <material name="Gray">
    <color rgba="0.8 0.8 0.8 1"/>
  </material>
  <turnGravityOff>false</turnGravityOff>
</gazebo>

and

Gripper

<!-- Link 3 -->
<link name="${prefix}link_3">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="package://robotiq_s_model_visualization/meshes/s-model_articulated/visual/link_3.STL" />
    </geometry>
    <material name="grey"/>
  </visual>
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="package://robotiq_s_model_visualization/meshes/s-model_articulated/collision/link_3.STL"/>
    </geometry>
    <material name="grey"/>
  </collision>
  <inertial>
    <origin rpy="0 0 0" xyz="0.01626 0.00049 0.0002"/>
    <mass value="0.03354"/>
    <inertia ixx="0.00000305151"
             ixy="0.00000089792"
             ixz="0.00000000249"
             iyy="0.00001427978"
             iyz="-0.00000001191"
             izz="0.00001264126"/>
  </inertial>
</link>

<gazebo reference="${prefix}link_3">
  <mu1>1.1</mu1>
  <mu2>1.1</mu2>
  <minDepth>0.001</minDepth>
</gazebo>

Link_3 is the finger tip of the gripper as seen in the video above.

Asked by gocarlos on 2017-03-14 11:52:09 UTC

Comments

Im using Gazebo 7.5, Ubuntu 14.04, ROS Indigo and ODE

Asked by gocarlos on 2017-03-14 11:54:11 UTC

Can you add a clarify statement as to why you think the friction is not being taken into account? What happens when you set the friction values significantly higher? Do you see the same behavior, or does something change?

Asked by nkoenig on 2017-03-14 17:58:31 UTC

Yes, I tried to put both at 1000 mu and mu2 in both files. The other values where unchanged. By saying that Gazebo does not take friction into account I meant that changing the friction coefficients does not make a difference in the behavior when grasping. The stone stays on the table even though the gripper presses with the maximal force.

Asked by gocarlos on 2017-03-15 10:05:09 UTC

Have you verified the stone's inertia is correct?

Asked by nkoenig on 2017-03-15 10:13:03 UTC

Im using those values: (mass is set to 1.0 (kg))

Can I check in gazebo if there is something "wrong" with those stones?

Asked by gocarlos on 2017-03-15 10:38:24 UTC

You can right click on your model (stone) and select View->Inertia. Your inertia should approximately surround your object's shape.

Asked by Carlos Agüero on 2017-03-17 10:39:46 UTC

It looks like the gripper might not be applying enough force to hold the rock. You can test the friction by changing gravity to have an Y component and see how the rock slides against the table.

Asked by chapulina on 2017-03-19 11:25:03 UTC

Answers