Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

How to convert *.urdf.xacro files to *.sdf for gazebo?

Dear all,

as with the latest gazebo version (1.7.12-s1367893033~precise) in groovy, it seems that our *.urdf.xacro files are finally not supported anymore.

I found out about the latest .sdf format (1.3) and already tried to update some of our files. I.e. I replaced

  <xacro:macro name="sick_s300_laser_gazebo_v0" params="name ros_topic update_rate min_angle max_angle">
    <gazebo reference="${name}_link">
      <sensor:ray name="${name}">
        <rayCount>541</rayCount>
        <rangeCount>541</rangeCount>
        <laserCount>1</laserCount>

        <origin>0.0 0.0 0.0</origin>
        <displayRays>false</displayRays>

        <minAngle>${min_angle*180.0/M_PI}</minAngle>
        <maxAngle>${max_angle*180.0/M_PI}</maxAngle>

        <minRange>0.05</minRange>
        <maxRange>30.0</maxRange>
        <resRange>0.03</resRange>
        <updateRate>${update_rate}</updateRate>
        <controller:gazebo_ros_laser name="gazebo_ros_${name}_controller" plugin="libgazebo_ros_laser.so">
          <gaussianNoise>0.005</gaussianNoise>
          <alwaysOn>true</alwaysOn>
          <updateRate>${update_rate}</updateRate>
          <topicName>${ros_topic}</topicName>
          <frameName>/${name}_link</frameName>
          <interface:laser name="gazebo_ros_${name}_iface" />
        </controller:gazebo_ros_laser>
      </sensor:ray>
      <material value="IPA/LightGrey" />
    </gazebo>
  </xacro:macro>

with

  <xacro:macro name="sick_s300_laser_gazebo_v0" params="name ros_topic update_rate min_angle max_angle">
    <gazebo reference="${name}_link">
    <sensor name="${name}" type="ray">
        <ray>
            <scan>
                <horizontal>
                    <samples>541</samples>
                    <resolution>1.0</resolution>
                    <min_angle>${min_angle*180.0/M_PI}</min_angle>
                    <max_angle>${max_angle*180.0/M_PI}</max_angle>
                </horizontal>
            </scan>
            <range>
                <min>0.05</min>
                <max>30.0</max>
                <resolution>0.03</resolution>
            </range>
        </ray>
    </sensor>       

      <material value="IPA/LightGrey" />
    </gazebo>
  </xacro:macro>

for the urdf.xacro files for one of our sensors.

However, if I then spawn our robot, I get the following message from gazebo:

fxm@sony-fxm:/opt/ros/groovy/stacks/simulator_gazebo/gazebo_worlds/worlds$ roslaunch gazebo_worlds empty_world.launch 
... logging to /home/fxm/.ros/log/320cbf70-bca0-11e2-9ff7-00271039ca78/roslaunch-sony-fxm-20823.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://sony-fxm:55478/

SUMMARY
========

PARAMETERS
 * /rosdistro
 * /rosversion
 * /use_sim_time

NODES
  /
    gazebo (gazebo/gazebo)
    gazebo_gui (gazebo/gui)

auto-starting new master
process[master]: started with pid [20837]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 320cbf70-bca0-11e2-9ff7-00271039ca78
process[rosout-1]: started with pid [20850]
started core service [/rosout]
process[gazebo-2]: started with pid [20864]
process[gazebo_gui-3]: started with pid [20876]
Gazebo multi-robot simulator, version 1.5.0
Copyright (C) 2013 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

Gazebo multi-robot simulator, version 1.5.0
Copyright (C) 2013 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

Warning [parser.cc:361] Converting a deprecated SDF source[/opt/ros/groovy/stacks/simulator_gazebo/gazebo_worlds/worlds/empty.world].
Set SDF value
  Version[1.2] to Version[1.3]
  Please use the gzsdf tool to update your SDF files.
    $ gzsdf convert [sdf_file]
Msg Waiting for master[ INFO] [1368540701.989137839]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...

Msg Connected to gazebo master @ http://127.0.0.1:11345
Msg Publicized address: 10.17.55.151
Msg Waiting for master
Msg Connected to gazebo master @ http://127.0.0.1:11345
Msg Publicized address: 10.17.55.151
Error [Events.hh:141] Events::ConnectWorldUpdateStart is deprecated in v 1.5.0. Please use Events::ConnectWorldUpdateBegin
Error [Events.hh:141] Events::ConnectWorldUpdateStart is deprecated in v 1.5.0. Please use Events::ConnectWorldUpdateBegin
Error [Events.hh:141] Events::ConnectWorldUpdateStart is deprecated in v 1.5.0. Please use Events::ConnectWorldUpdateBegin
[ INFO] [1368540703.812490419]: joint trajectory plugin missing <updateRate>, defaults to 0.0 (as fast as possible)
Error [Events.hh:141] Events::ConnectWorldUpdateStart is deprecated in v 1.5.0. Please use Events::ConnectWorldUpdateBegin
[ INFO] [1368540703.842767312, 0.023000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1368540703.883032363, 0.057000000]: Starting to spin physics dynamic reconfigure node...
Warning [parser.cc:377] SDF has no <sdf> element in file[data-string]
Dbg extension [<sensor name="base_laser_front" type="ray"><ray><scan><horizontal><samples>541</samples><resolution>1.0</resolution><min_angle>-135.000315689</min_angle><max_angle>135.000315689</max_angle></horizontal></scan><range><min>0.05</min><max>30.0</max><resolution>0.03</resolution></range></ray></sensor>] not converted.
Dbg extension [<sensor name="base_laser_rear" type="ray"><ray><scan><horizontal><samples>541</samples><resolution>1.0</resolution><min_angle>-135.000315689</min_angle><max_angle>135.000315689</max_angle></horizontal></scan><range><min>0.05</min><max>30.0</max><resolution>0.03</resolution></range></ray></sensor>] not converted.
Dbg [base_footprint] has no parent joint
Warning [parser.cc:314] parse from urdf.

The robot spawns within gazebo but there no sensor message is published. It is similar for our controllers. They don't work anymore as well.

My questions now are:

Why are the gazebo extensions not converted? Is there something wrong?

What is best practise to convert .urdf.xacro files into the new .sdf format?
Where can I find examples? Has the PR2 been updated yet?

With best regards,

Felix