Robotics StackExchange | Archived questions

Object slips from gripper fingers when grasping in simulation

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 : KukagripperGazebo_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>0.1</mu2>
    <fdir1>1 0 0</fdir1>
    <minDepth>0.01</minDepth>
  </gazebo>

</robot>

3)The gripper fingers controller :

gripper_controller:
  type: effort_controllers/JointTrajectoryController
  joints:
       - Mors_prismatic1_joint
       - Mors_prismatic2_joint
       - Mors_prismatic3_joint
  gains:
    Mors_prismatic1_joint:  {p: 50.0, d: 10.0, i: 0.01, i_clamp: 1.0}
    Mors_prismatic2_joint:  {p: 50.0, d: 10.0, i: 0.01, i_clamp: 1.0}
    Mors_prismatic3_joint:  {p: 50.0, d: 10.0, i: 0.01, i_clamp: 1.0}

4)The empty world configuration :

<?xml version="1.0"?>

<gazebo:world
  xmlns:xi="http://www.w3.org/2001/XInclude"
  xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
  xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
  xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
  xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window"
  xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param"
  xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
  xmlns:geo="http://willowgarage.com/xmlschema/#geo"
  xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
  xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
  xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
  xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
  xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
  xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
  xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
  xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >

  <thread>4</thread>
  <verbosity>5</verbosity>

  <!-- cfm is 1e-5 for single precision -->
  <!-- erp is typically .1-.8 -->
  <!-- here's the global contact cfm/erp -->
  <physics:ode>
    <stepTime>0.001</stepTime>
    <gravity>0 0 -9.8</gravity>
    <cfm>0.0000000001</cfm>
    <erp>0.2</erp>
    <quickStep>true</quickStep>
    <quickStepIters>10</quickStepIters>
    <quickStepW>1.3</quickStepW>
    <contactMaxCorrectingVel>100.0</contactMaxCorrectingVel>
    <contactSurfaceLayer>0.001</contactSurfaceLayer>
  </physics:ode>

  <geo:origin>
    <lat>37.4270909558</lat><lon>-122.077919338</lon>
  </geo:origin>

  <rendering:gui>
    <type>fltk</type>
    <size>480 320</size>
    <pos>0 0</pos>
    <frames>
      <row height="100%">
        <camera width="100%">
          <xyz>0.3 0 3</xyz>
          <rpy>0 90 90</rpy>
        </camera>
      </row>
    </frames>
  </rendering:gui>


  <rendering:ogre>
    <ambient>0.5 0.5 0.5 0.5</ambient>
    <sky>
      <material>Gazebo/CloudySky</material>
    </sky>
    <grid>false</grid>
    <maxUpdateRate>10.</maxUpdateRate>
    <shadowTechnique>none</shadowTechnique>
    <shadows>false</shadows>
  </rendering:ogre>

  <!-- ground plane -->
  <model:physical name="gplane">
    <xyz>0 0 0</xyz>    
    <rpy>0 0 0</rpy>
    <static>true</static>

    <body:plane name="plane">
      <geom:plane name="plane">
        <laserRetro>2000.0</laserRetro>
        <mu1>50.0</mu1>
        <mu2>50.0</mu2>
        <kp>1000000000.0</kp>
        <kd>1.0</kd>
        <normal>0 0 1</normal>
        <size>51.3 51.3</size>
        <segments>10 10</segments>
        <uvTile>100 100</uvTile>
        <material>Gazebo/GrayGrid</material>
      </geom:plane>
    </body:plane>
  </model:physical>

<!--
  <model:physical name="walls">
    <include embedded="false">
      <xi:include href="tests/willow-walls.model" />
    </include>
  </model:physical>
-->
<!--
  <model:physical name="willow_map">
   <xyz>-25.65 25.65 1.0</xyz>  
   <rpy>180 0 0</rpy>
   <static>true</static>
   <body:map name="willow_map_body">
     <geom:map name="willow_map_geom">
       <image>willowMap.png</image>
       <threshold>200</threshold>
       <granularity>1</granularity>
       <negative>false</negative>
       <scale>0.1</scale>
       <offset>0 0 0</offset>
       <material>Gazebo/Rocky</material>
     </geom:map>
   </body:map>
  </model:physical>
-->

  <!-- White Point light -->
  <model:renderable name="point_white">
    <xyz>0.0 0.0 8</xyz>
    <enableGravity>false</enableGravity>
    <light>
      <type>point</type>
      <diffuseColor>0.5 0.5 0.5</diffuseColor>
      <specularColor>.1 .1 .1</specularColor>
      <attenuation>0.2 0.1 0</attenuation>
      <range>10</range>
    </light>
  </model:renderable>

</gazebo:world>

5)My Gazebo Launch file :

    <?xml version="1.0"?>
<launch>
    <arg name="paused" default="false"/>

  <!-- remap topics to conform to ROS-I specifications -->
  <remap from="/arm_controller/follow_joint_trajectory" to="/joint_trajectory_action" />
  <remap from="/arm_controller/state" to="/feedback_states" />
  <remap from="/arm_controller/command" to="/joint_path_command"/>

  <!-- startup simulated world -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find kuka_kr6_gazebo)/worlds/empty.world"/>
    <arg name="gui" value="true"/>
    <arg name="paused" value="true"/>
  </include>

  <!-- urdf xml robot description loaded on the Parameter Server, converting the xacro into a proper urdf file-->
  <include file="$(find kuka_kr6_gazebo)/launch/load_kr6r900sixx.launch" />

  <!-- push robot_description to factory and spawn robot in gazebo -->
  <!-- <node name="kuka_kr6r900sixx_spawn" pkg="gazebo_ros" type="spawn_model" output="screen" args="-urdf -param robot_description -model kuka_kr6r900sixx" />-->
  <node name="kuka_kr6r900sixx_spawn" pkg="gazebo_ros" type="spawn_model" output="screen" args="-urdf -param robot_description -model kuka_kr6r900sixx -J joint_a1 0.0 -J joint_a2 -0.8915 -J joint_a3 1.4187   -J joint_a4 -0.0535   -J joint_a5 1.2381   -J joint_a6 0.0 -unpause" />


  <node name="cylinder_spawn" pkg="gazebo_ros" type="spawn_model" output="screen" args="-urdf -param cylinder_description -model cylinder -x 0.65 -y 0 -z 0.01" />


  <!-- convert joint states to TF transforms for rviz, etc -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
  output="screen">
  </node>


  <!-- init and start Gazebo ros_control interface -->
  <include file="$(find kuka_kr6_gazebo)/launch/kr6r900sixx_control.launch"/> 


</launch>

6)The applied forces to open and close the gripper :

<group_state name="open_gripper" group="gripper">
    <joint name="Mors_prismatic1_joint" value="1000" />
    <joint name="Mors_prismatic2_joint" value="1000" />
    <joint name="Mors_prismatic3_joint" value="1000" />
</group_state>

<group_state name="close_gripper" group="gripper">
    <joint name="Mors_prismatic1_joint" value="-1000" />
    <joint name="Mors_prismatic2_joint" value="-1000" />
    <joint name="Mors_prismatic3_joint" value="-1000" />
</group_state>

Can you please tell me what i am doing wrong, i red every topic on the subject but no proposed solution helped. I am on Gazebo 9.8 and Ubuntu 16.04.

Thank you in advance.

Asked by ASTRE on 2019-04-16 10:00:52 UTC

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 (1 0 0 ) rather than in z direction which would be needed in your case (0 0 1). And I found something else. Depending on the sdf version, you can set the friction model (at least at version 1.6) look here

Asked by steradiant on 2019-04-20 09:42:01 UTC

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

Asked by pmuthu2s on 2019-04-23 06:49:17 UTC

The Jennifer's grasp plugin is what worked for me. A link for my simulation can be found in here : https://github.com/Meguenani/kuka_kr6r900sixx_moveit_gazebo_setup-master

Asked by ASTRE on 2019-12-10 18:02:44 UTC

Answers

Try to also set 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 to a higher value rather than . In my case, I kept both values high to make the gripping also robust against tilting actions.

You can also add the 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.

Asked by steradiant on 2019-04-17 05:33:59 UTC

Comments

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

Asked by RobotBoy on 2020-04-11 07:12:13 UTC

Comments