Robotics StackExchange | Archived questions

<sensor> elements in .urdf disappearing when converting to .sdf

Hello everyone, I am working on the URDF description of the IIT COMAN robot, and I'm having some difficulties in inserting the gazebo force_torque sensor in my robot description. Inserting the element directly into the sdf file solves the problem, but at the moment we are working on the urdf description (which gets converted to sdf using gzsdf). Putting the element inside the .gazebo or inside the .urdf doesn't seem to make a difference. The description of the robot we are using is https://github.com/EnricoMingo/iit-coman-ros-pkg Could someone give me instructions on how to correctly insert the sensor in the urdf or gazebo files? So far I tried the following syntax:

In the .gazebo file

<gazebo reference="LElbj">
    <cfmDamping>1</cfmDamping>
    <provideFeedback>true</provideFeedback>
    <sensor type="force_torque" name="LElbj_FT">
    <always_on>true</always_on>
    <visualize>true</visualize>
    <update_rate>1000</update_rate>
    </sensor>
</gazebo>

In the .gazebo, after including the right xmlns:sensor in the element

<gazebo reference="LElbj">
<cfmDamping>1</cfmDamping>
<provideFeedback>true</provideFeedback>
<sensor:force_torque name="LElbj_FT">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>1000</update_rate>
</sensor:force_torque>

In the .urdf

<joint name="RElbj" type="revolute">
<parent link="RShy"/>
<child link="RElb"/>
<origin xyz="0.0 0.0 -0.13519152999999998" rpy="0 0 0" />
<axis xyz="0 1 0" />
<limit velocity="4.0" effort="50" lower="-2.3562" upper="0.0" />
<sensor type="force_torque" name="Relbj_FT">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>1000</update_rate>
</sensor>

Obviously doing the same thing in the .sdf file works correctly (as shown in the force_torque_demo.world example). Any help would be greatly appreciated.

Asked by arocchi on 2013-10-13 13:05:03 UTC

Comments

Hi @arocchi, did you solve it?

Asked by Francisco on 2014-06-05 08:52:14 UTC

Answers

The first syntax for your .gazebo file is correct. Have you included the .gazebo file in your .xacro file?

I believe you can also directly insert

<gazebo reference="LElbj">
    <cfmDamping>1</cfmDamping>
    <provideFeedback>true</provideFeedback>
    <sensor type="force_torque" name="LElbj_FT">
    <always_on>true</always_on>
    <visualize>true</visualize>
    <update_rate>1000</update_rate>
    </sensor>
</gazebo>

into you .urdf file.

Asked by nkoenig on 2013-10-14 11:54:11 UTC

Comments

yes, the .gazebo is included in the .xacro file (coman.gazebo is included by coman_robot.urdf.xacro: )

Asked by arocchi on 2013-10-14 12:04:00 UTC

Hi @nkoenig, It doesn't work. I think is a problem with the sensor tag within a joint because if I put only provideFeedback It's added to the .sdf. I'm working with gazebo 1.9.5

Asked by Francisco on 2014-06-05 08:50:21 UTC

it is a bug in sdformat which I reported some time ago, still not fixed. https://bitbucket.org/osrf/sdformat/issue/38/force_torque-sensors-not-handled-by

Asked by arocchi on 2014-06-06 03:47:02 UTC