Gazebo | Ignition | Community
Ask Your Question
2

Gazebo contact sensor added to a robot link in urdf file is not working as expected?

asked 2016-12-26 06:51:38 -0500

SP gravatar image

I have added a contact sensor to one of the finger links of a robot's gripper as follows:

 <link name="bh_finger_13_link">
    <inertial>
      <mass value="0.01"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
    </inertial>
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
         <mesh file
  name="package://bh262_description/meshes/bhand/finger_tip.dae" />

   </geometry>
       <material name="Yellow" />
    </visual>
    <collision name="bh_finger_13_collision">
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <geometry name="bh_finger_13_collision">
         <mesh filename="package://bh262_description/meshes/bhand/finger_tip.dae" />
      </geometry>
        <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
    </collision>
</link>

<gazebo reference="bh_finger_13_link">
   <sensor name='my_contact' type='contact'>
       <plugin name="my_plugin" filename="libcontact.so"/>
          <contact>
            <collision>bh_finger_13_link_collision</collision>
          </contact>
        <update_rate> 5 </update_rate>
        </sensor>
  </gazebo>

On lauching the urdf file, I am getting the gazebo topics /gazebo/default/wam/bh_finger_13_link/my_contact and /gazebo/default/wam/bh_finger_13_link/my_contact/contacts. However, on echoing these topics, I am not getting the collision data. In order to debug this issue, I have also added a contact sensor to a box model sdf, and made the finger link to touch this object. On echoing the topic associated with the contact sensor of the box model, I am getting the collision of the box with the finger link, but on echoing the topic associated with the finger link, I am not getting the same collision information. I am not able to figure out the reason behind this discrepancy. Any help is much appreciated.

edit retag flag offensive close merge delete

Comments

Did you find any solution ? I have exaclty the same issue: i'm able to have collision data from the sensor contact type in a world model but when i do it inside a robot then the collision is empty and on the dedicated topic I only have timestamps

TTDM gravatar imageTTDM ( 2017-01-18 09:06:52 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2017-01-19 04:09:06 -0500

TTDM gravatar image

updated 2018-04-17 10:59:56 -0500

I found a work around !!!!!

Investigating what cause the issue, I found that there are issues parsing from urdf to sdf especially in the gazebo flag. Here is a link to a question in ros answer that does raise this issue : http://answers.gazebosim.org/question...

You can check on your own with editing an urdf from a xacro (rosrun xacro xacro.py -o robot.urdf robot.xacro) and then a sdf from an urdf (gz sdf -p robot.urdf > robot.sdf), you will see that the issues are with the collision flags, both the one inside the gazebo link and the one inside the link.

So their are 2 issues :

  • if you directly define a collision inside the <gazebo> flag, the urdf -> sdf parser does not allow it instead puts <collision>__default__</collision>
  • the 2nd one is that the collision name that you setup in the link part is modified but this modification does not occur in the gazebo collision : If i go back to your exemple, in the link, you will NOT create a "bh_finger_13_collision" collision but you will create a "bh_finger_13_collision_collision" but in the gazebo part you will still call "bh_finger_13_collision" which does not exists.

In order to make it work, this is awful but I believe the only way at the moment, you have to change the names of your collision according to this _collision add on only one side. For exemple you could still call your collision 'bh_finger_13_collision' in the link but then in the gazebo part, you need to call it "bh_finger_13_collision_collision"

TTDM,

Supplementary note : in complex projects, there are usually other adds to the name of the collision ( in my project, with my collision box being called "mav_collision_box", the final name on the sdf of my collision box is : shredder/base_link_fixed_joint_lump__mav_collision_box_collision and i have to call that exact name on inside the <gazebo> flag) so you should really generate your sdf using the two command lines i gave previously then manually search for the name of your collision and put it into the gazebo part (of your xacro file)

edit flag offensive delete link more

Comments

Thank you! This is ugly, but fixed my issue. Mods - Can this be fixed?

dcconner gravatar imagedcconner ( 2017-03-07 19:15:47 -0500 )edit

Thank you! This also worked for me with ROS Indigo and Gazebo7.

jiriker gravatar imagejiriker ( 2017-03-07 23:51:36 -0500 )edit

I've already created an issue which describes the same behavior exactly one year ago, but it is still not assigned. You can find it here: https://bitbucket.org/osrf/sdformat/issues/113/parsing-from-urdf-to-sdf-does-not-handle. Follow the linked repository for details.

alextoind gravatar imagealextoind ( 2017-03-08 03:12:31 -0500 )edit

well the link in my answer is to your topic ;) What i did is basically explain how to go around it in a user point of vue which was not clearly stated in your post since your goal differ and was more to highligth the issue than to deal with it as a user ;)

TTDM gravatar imageTTDM ( 2017-03-09 02:10:22 -0500 )edit

Sure and thanks for that. I was just pointing out that I added the issue reference yesterday (I completely forgot to add it before).

alextoind gravatar imagealextoind ( 2017-03-09 02:16:01 -0500 )edit

I found that if you don't specify the collision name, you get something a lot nicer. E.g. if I specify the collision name (name="palm") I get: {link name}_fixed_joint_lump__palm_collision, but if I leave it empty I get: {link name}_collision. My recipe is then to simply leave the collision name of the link empty, and name the contact collision element as {link_name}_collision.

hamzamerzic gravatar imagehamzamerzic ( 2017-05-18 07:32:16 -0500 )edit

How did you load the edited sdf file?

Feynman gravatar imageFeynman ( 2018-01-25 10:13:26 -0500 )edit

HI, just saw your comment, you need to create the sdf file only to check it and then do the modifications on the xacro file ( but I guess that you solved it since January )

TTDM gravatar imageTTDM ( 2018-04-17 10:57:51 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2016-12-26 06:51:38 -0500

Seen: 9,866 times

Last updated: Apr 17 '18