<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
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 <robot> 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>
</gazebo>
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>
</joint>
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.
Hi @arocchi, did you solve it?