Robotics StackExchange | Archived questions

Object slips out of the gripper after jitters

I am trying to make robot arm grasp a cylinder object but when ever the gets in the grasp and the gripper closes, it starts vibrating and the object appears to slip out of it. I am using a position_controller for gripper and the rest of the arm. The problem I can think of could be with the controller as it tries to reach a position which it cannot due to collision with the object so the pid controller starts shaking it.

Pls answer if you have any insight on this. Thanks

<link name="${prefix}gripper_finger1">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <geometry>
      <!--box size="0.015 0.0229 0.0475"/-->
      <mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger1.dae"/>
    </geometry>
  </visual>
  <collision name="${prefix}gripper_finger1_collision">
    <origin xyz="0 0 0" rpy="0 0 0" />
    <geometry>
      <box size="0.015 0.0229 0.1"/>
  <mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger1.dae"/>
    </geometry>
  </collision>
  <inertial>
    <mass value="0.01"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <inertia ixx=".0000027" iyy=".0000027" izz=".0000027"
              ixy="0" ixz="0" iyz="0"/>
  </inertial>
</link>

 <gazebo reference="${prefix}gripper_finger1">
  <kp>1000000.0</kp>
  <kd>1.0</kd>
  <mu1>200.0</mu1>
  <mu2>100.0</mu2>
  <minDepth>0.001</minDepth>
</gazebo>


<transmission name="tran8">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}gripper_joint">
  <hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor8">
  <hardwareInterface>EffortJointInterface</hardwareInterface>
</actuator>

<!--mimic joint="${prefix}gripper_joint" multiplier="-1"/-->

<link name="${prefix}gripper_finger2">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0" />
    <geometry>
  <!--box size="0.015 0.0229 0.0475"/-->
      <mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger2.dae"/>
    </geometry>
  </visual>
  <collision name="${prefix}gripper_finger2_collision">
    <origin xyz="0 0 0" rpy="0 0 0" />
    <geometry>
      <box size="0.015 0.0229 0.1"/><!--0.0475-->
  <!--mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger2.dae"/-->
    </geometry>
  </collision>
  <inertial>
    <mass value="0.01"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <inertia ixx=".0000027" iyy=".0000027" izz=".0000027"
              ixy="0" ixz="0" iyz="0"/>
  </inertial>
</link>

<gazebo reference="${prefix}gripper_finger2">
  <kp>1000000.0</kp>
  <kd>1.0</kd>
  <mu1>200.0</mu1>
  <mu2>100.0</mu2>
  <minDepth>0.001</minDepth>
</gazebo>



<transmission name="tran9">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="${prefix}gripper_joint2">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor9">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
    </actuator>

This is the updated urdf of the gripper

  <?xml version="1.0"?>
<robot name="mug">
<link name="coke_can">
    <inertial>
      <mass value="0.1" />
      <!-- center of mass (com) is defined w.r.t. link local coordinate system -->
      <origin xyz="0 0 0.06" /> 
      <inertia  ixx="0.1" ixy="0.0"  ixz="0.0"  iyy="0.1"  iyz="0.0"  izz="0.1" />
    </inertial>
    <visual>
      <!-- visual origin is defined w.r.t. link local coordinate system -->
      <origin xyz="0 0 -0.18" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://mbot_description/meshes/coke_can.dae" scale="0.001 0.001 0.001" />
      </geometry>
    </visual>
    <collision>
      <!-- collision origin is defined w.r.t. link local coordinate system -->
      <origin xyz="0 0 -0.18" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://mbot_description/meshes/coke_can.dae" scale="0.001 0.001 0.001" />
      </geometry>
    </collision>
  </link>
 <gazebo reference="my_cylinder">
    <selfCollide>false</selfCollide>
    <material>Gazebo/Blue</material>
    <turnGravityOff>false</turnGravityOff>
    <static>false</static>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
    <mu1>200.0</mu1>
    <mu2>100.0</mu2>
    <minDepth>0.001</minDepth>
  </gazebo>
</robot>

      </transmission>

This is the updated object

<?xml version="1.0" ?>
<sdf version="1.4">
  <world name="default">
    <include>
      <uri>model://ground_plane</uri>
      <material>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Orange</name>
          </script>
      </material>
    </include>

    <!-- Global light source -->
    <include>
      <uri>model://sun</uri>
    </include>

    <!--include>
      <uri>model://rockin_d213</uri>
    </include-->

    <!--include>
      <uri>model://grasping</uri>
    </include-->

    <physics type="ode">
      <real_time_update_rate>1500</real_time_update_rate>
      <ode>
        <solver>
          <type>quick</type>
          <iters>200</iters>
        </solver>
      </ode>
    </physics>

    <!-- Focus camera on tall pendulum -->
    <gui fullscreen='0'>
      <camera name='user_camera'>
        <pose>4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190</pose>
        <view_controller>orbit</view_controller>
      </camera>
    </gui>

  </world>
</sdf>

This is the world file

grasping demonstration_1

grasping demonstration_2

Finally captured the demonstration in the above link.

Asked by rilch on 2016-06-21 09:15:33 UTC

Comments

please post your world file with your gripper demonstrating the issue so we can help

Asked by Peter Mitrano on 2016-06-21 10:57:47 UTC

Answers

Some suggestions:

1) add following blocks to your urdf for every joint:

  <gazebo reference="[joint name]">
    <implicitSpringDamper>1</implicitSpringDamper>
  </gazebo>

Sometimes I think we should have these settings on by default.

Also, try to come up with as realistic as possible material properties kp, mu1, mu2. Set contact dissipation coefficient kd to 1 to help stabilize contacts. Also, setting minDepth margin to a small non-zero number prevents contact from jumping in and out of existence. For example:

<gazebo reference="[links in contact]">
  <kp>1000000.0</kp>
  <kd>1.0</kd>
  <mu1>1.0</mu1>
  <mu2>1.0</mu2>
  <minDepth>0.001</minDepth>
</gazebo>

2) The cylinder has mass value of 0.1kg, but Ixx of 1.0 kg m^2, which is not very physically realistic. One should always start with a more physically realistic object model.

3) As a rule of thumb, if the inertia ratio across contact constraint formed by the object and the gripper finger is on the order of or greater than 1e3, consider increasing number of inner iterations from default of 50, do a quick ad-hoc search by doubling iterations and look for improvement in behavior. Alternatively, plot iterations vs rms_error and check trend.

4) Consider increasing joint damping for the fingers. Without modeling high gear ratio gearbox joints and the underlying motor and gear inertia, the stabilizing effects of such mechanisms is easiest replaced by larger joint damping in the time being. Physically, my go to damping coefficient for triaging a hard to converge system ranges anywhere between 0.1 to 30 (effort/joint_vel). Until such time validation or more accurate model data are available.

5) Are the joint effort limits realistic? 0.1N seems low for holding up a 0.1kg cylinder (under gravity, downward force is 9.81N).

6) Consider tuning the PID gains of your controller. We can go into details on this as needed.

Asked by hsu on 2016-06-21 13:38:36 UTC

Comments

Thanks for such a detailed answer. But could you elaborate on point 3. For, example what exactly are inner iterations and rms_error

Asked by rilch on 2016-06-21 14:09:49 UTC

It still doesn't work! When ever gripper gets a grasp on the object it slips over it while lifting and other times object passes through the gripper

Asked by rilch on 2016-06-22 07:15:34 UTC

I am having the same issue. @rilch did you manage to solve this?

Asked by hamzamerzic on 2017-06-15 07:50:12 UTC

I am having the same issue. @rilch did you manage to solve this?

Asked by hamzamerzic on 2017-06-15 07:50:55 UTC