Gazebo | Ignition | Community
Ask Your Question
0

Setting contact coefficients

asked 2016-07-25 01:13:29 -0500

intelharsh gravatar image

updated 2016-07-28 03:34:34 -0500

We have designed our own magnetic gripper for a pick and place application. I was successfully able to import this and visualize the inertias in Gazebo.

image description

But when I visualize the contacts, the vector keeps on moving frantically. Even though the movements of the arm itself is very smooth, when it comes in contact with another object, it starts vibrating. https://youtu.be/eP29QGYoQhY

I dug into PR2 gripper because it behaves very realistically when it is in contact with other objects and tried to implement the contact coefficients

Attempt 1 :

<surface>
  <friction>
    <ode>
      <mu>0.01</mu>
      <mu2>0.01</mu2>
      <fdir1>0 0 1</fdir1>
      <slip1>0.0</slip1>
      <slip2>0.0</slip2>
    </ode>
  </friction>
  <contact>
    <ode>
      <min_depth>0.005</min_depth>
      <kp>1e8</kp>
    </ode>
  </contact>
</surface>

Attempt 2 : This is exactly like the PR2 gripper

<gazebo reference="gripper_link">
  <turnGravityOff>true</turnGravityOff>
  <selfCollide>false</selfCollide>
  <mu1 value="${finger_tip_mu}" />
  <mu2 value="${finger_tip_mu}" />
  <kp  value="10000000.0" />
  <kd  value="1.0" />
</gazebo>
<gazebo reference="gripper_joint">
  <stopKd value="${finger_stop_kd}" />
  <stopKp value="${finger_stop_kp}" />
  <fudgeFactor value="${finger_fudge_factor}" />
  <provideFeedback value="true"/>
</gazebo>

This is my entire gripper xacro file :

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:macro name="gripper_link" >
  <link name="gripper">    
    <inertial>
      <mass value="0.6" />
      <origin xyz="-0.02 0 0.04" />
      <inertia ixx="0.0003" ixy="0.0"  ixz="0.0"
               iyy="0.0009" iyz="0.0"
               izz="0.0008"/>
    </inertial>
    <visual>
       <origin xyz="-0.02 0 0.04" />
      <geometry>
        <mesh filename="package://ur5_pnp/meshes/gripper.stl" scale="0.01 0.01 0.01"/>
      </geometry>
    </visual>
    <collision>
       <origin xyz="-0.02 0 0.04" />
      <geometry>
        <mesh filename="package://ur5_pnp/meshes/gripper.stl" scale="0.01 0.01 0.01"/>
      </geometry>
       <surface>
      <friction>
        <ode>
          <mu>0.01</mu>
          <mu2>0.01</mu2>
          <fdir1>0 0 1</fdir1>
          <slip1>0.0</slip1>
          <slip2>0.0</slip2>
        </ode>
      </friction>
      <contact>
        <ode>
          <min_depth>5</min_depth>
          <kp>1e8</kp>
        </ode>
      </contact>
    </surface>
    </collision>
  </link>
  <gazebo reference="my_gripper">
    <material>Gazebo/Blue</material>
  </gazebo>

  </xacro:macro>
</robot>

But both the times I get the exact same behaviour. Is it something to do with friction or is it some other issue? This is my gripper's stl file

Edit 1: This gripper has no moving parts which is to simulate a magnetic gripper.

Edit 2: Updated link for STL file

edit retag flag offensive close merge delete

Comments

I can't seem to access your stl file. Is there an alternate way for you to post it?

nkoenig gravatar imagenkoenig ( 2016-07-27 10:01:45 -0500 )edit

Your gripper xacro file is a mixture of both URDF and SDF. You can't have a `<surface>` tag in URDF.

nkoenig gravatar imagenkoenig ( 2016-07-27 10:04:50 -0500 )edit

I have updated the link for the file. Is it accessible now? So is the ´Attempt 2´ correct way to define the contact / friction parameters in URDF?

intelharsh gravatar imageintelharsh ( 2016-07-28 03:38:43 -0500 )edit

Hey, there, I realize this question of your is really old but as I'm currently working on the same type problem I want to check and see if you managed a solution. Any tips to share with me?

raequin gravatar imageraequin ( 2018-08-08 21:12:14 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2016-07-25 10:39:37 -0500

nkoenig gravatar image

The problem could be related to the maximum velocity (<max_vel>) applied to contacts.

SDF snippet:

  <collision name="collision_name">
    <surface>
      <contact>
        <ode>
          <kp>1000000.000000</kp>
          <kd>1.000000</kd>
          <max_vel>100.000000</max_vel>
          <min_depth>0.000000</min_depth>
        </ode>
      </contact>
    </surface>
  </collision>
edit flag offensive delete link more

Comments

Sorry but still the same problem

intelharsh gravatar imageintelharsh ( 2016-07-26 02:46:47 -0500 )edit

The arm still passes through the object with high vibrations which sends the robot flying. Also, I just noticed that you mentioned it as SDF snippet. Can't I add this in URDF as `gazebo reference`?

intelharsh gravatar imageintelharsh ( 2016-07-26 07:09:33 -0500 )edit

You can use gazebo reference in URDF.

nkoenig gravatar imagenkoenig ( 2016-07-27 10:01:10 -0500 )edit

Since I'm currently working on the same type problem I read through this post and your answer. Question: shouldn't max_vel be set to something smaller than the default of 0.01? You gave a value of 100 in your answer. What gives, eh?

raequin gravatar imageraequin ( 2018-08-08 21:14:11 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-07-25 01:13:29 -0500

Seen: 7,599 times

Last updated: Jul 28 '16