Gazebo 1.9 fails to load URDF (which works in RVIZ and is validate by urdfdom)
Hi,
I have this irritating issue that I can not spawn my URDF model in gazebo. The model has been verified with urdfdom, and I can successfully use it in RVIZ.
When I try to do so I get the following error:
Warning [parser_urdf.cc:1010] multiple inconsistent <self_collide> exists due to fixed joint reduction overwriting previous value [false] with [true].
Error [parser.cc:697] XML Element[sensor:ray], child of element[link] not defined in SDF. Ignoring.[link]
Error [parser.cc:688] Error reading element <link>
Error [parser.cc:688] Error reading element <model>
Error [parser.cc:348] Unable to read element <sdf>
Error [parser.cc:299] parse as old deprecated model file failed.
Error [World.cc:1469] Unable to read sdf string [..entire urdf model here]
The actual urdf model is here:
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from youbot.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="youbot" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- The following included files set up definitions of parts of the robot body -->
<!-- misc common stuff? -->
<!-- youbot base -->
<!-- youbot plate -->
<!-- youbot arm -->
<!-- youbot gripper -->
<!-- generic simulator_gazebo plugins for starting mechanism control, ros time, ros battery -->
<gazebo>
<controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<interface:audio name="gazebo_ros_controller_manager_dummy_iface"/>
</controller:gazebo_ros_controller_manager>
<controller:gazebo_ros_power_monitor name="gazebo_ros_power_monitor_controller" plugin="libgazebo_ros_power_monitor.so">
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<timeout>5</timeout>
<interface:audio name="power_monitor_dummy_interface"/>
<powerStateTopic>power_state</powerStateTopic>
<powerStateRate>10.0</powerStateRate>
<fullChargeCapacity>87.78</fullChargeCapacity>
<dischargeRate>-474</dischargeRate>
<chargeRate>525</chargeRate>
<dischargeVoltage>15.52</dischargeVoltage>
<chargeVoltage>16.41</chargeVoltage>
</controller:gazebo_ros_power_monitor>
</gazebo>
<!-- materials for visualization -->
<material name="Orange">
<color rgba="1.0 0.4 0.0 1.0"/>
</material>
<material name="Grey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<material name="DarkGrey">
<color rgba="0.3 0.3 0.3 1.0"/>
</material>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="Black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="Red">
<color rgba="1.0 0.0 0.0 1.0"/>
</material>
<material name="Green">
<color rgba="0.0 1.0 0.0 1.0"/>
</material>
<!-- Now we can start using the macros included above to define the actual youbot -->
<!-- The first use of a macro. This one was defined in base.urdf.xacro above.
A macro like this will expand to a set of link and joint definitions, and to additional
Gazebo-related extensions (sensor plugins, etc). The macro takes an argument, name,
that equals "base", and uses it to generate names for its component links and joints
(e.g., base_link). The included origin block is also an argument to the macro. By convention,
the origin block defines where the component is w.r.t its parent ...