Gazebo | Ignition | Community
Ask Your Question
0

Plugins via URDF not parsing

asked 2013-04-15 00:09:46 -0600

JezzaC gravatar image

Hi all,

I've updated my Gazebo that came packaged with ROS Groovy as my laptop graphics card hated it. And am now running Gazebo 1.4.

I can spawn urdf models and have the ros api plugin working fine. When it comes to getting my robot controller plugin working I seem to hit a bit of a wall. Here is an example bit of code that has the same issue, which is taken from this tutorial.

<?xml version="1.0" ?>
<robot name="single_joint">
  <gazebo reference="base">
    <material>Gazebo/GrassFloor</material>
  </gazebo>
  <link name="world"/>
  <joint name="link_joint" type="continuous">
    <axis xyz="0 0 1"/>
    <parent link="world"/>
    <origin rpy="0 0 0" xyz="0 0 1"/>
    <child link="link"/>
    <limit effort="100" velocity="100" k_velocity="0" />
    <joint_properties damping="0.1" friction="1.0" />
  </joint>
  <link name="link">
    <inertial>
      <mass value="10"/>
      <origin xyz="0 0 0"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 1" xyz="0 0 0"/>
      <geometry>
        <box size="0.2 1.0 0.2"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 1" xyz="0 0 0"/>
      <geometry>
        <box size="0.2 1.0 0.2"/>
      </geometry>
    </collision>
  </link>
  <gazebo reference="link">
    <material>Gazebo/GrassFloor</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>

   <gazebo>
    <controller:gazebo_ros_force name="gazebo_ros_force" plugin="libgazebo_ros_force.so">
      <alwaysOn>true</alwaysOn>
      <update>100</update>
      <updateRate>100.0</updateRate>
      <bodyName>link</bodyName>
      <topicName>force</topicName>
    </controller:gazebo_ros_force>
  </gazebo>
</robot>

and running with the usual;

rosmake gazebo_worlds
roslaunch gazebo_worlds empty_world.launch
rosrun gazebo spawn_model -file object.urdf -urdf -z 1 -model my_object

I get;

...    
[ INFO] [1365999923.235584629, 0.076000000]: Starting to spin physics dynamic reconfigure node...
Warning [parser.cc:377] SDF has no <sdf> element in file[data-string]
Error [parser.cc:712] XML Element[turnGravityOff], child of element[link] not defined in SDF. Ignoring.[link]
Error [parser.cc:703] Error reading element <link>
Error [parser.cc:703] Error reading element <model>
Error [parser.cc:369] Unable to read element <sdf>
Error [parser.cc:319] parse as old deprecated model file failed.
Error [World.cc:1299] Unable to read sdf string
...

I have found that the urdf method of getting gazebo to load the plugin seems to fail in the parser.cc which then results in gazebo falling back to try parse it as a sdf, which it then fails further on.

Now I know the intent is to do away with urdf's eventually, but this method of plugging in the plugin into gazebo seemed to work on my other machine with ROS-Fuerte and Gazebo 1.2, and even seems to work on my colleges laptop with ROS-Groovy and the inbuilt ROS gazebo (1.3).

Bit of a head scratcher. Should I;

  • update my Gazebo to 1.5/1.6 instead? (i.e. is 1.4 a bit of a dog?)
  • revert my gazebo to a standalone 1.3.
  • bite the bullet and figure out a way to convert all my ...
(more)
edit retag flag offensive close merge delete

Comments

Did the exact code above work on your other machine?

ffurrer gravatar imageffurrer ( 2013-04-16 11:16:07 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2013-04-16 11:14:28 -0600

ffurrer gravatar image

updated 2013-04-16 11:34:47 -0600

I'm not sure what your problem is, exactly, maybe you want to exchange the <controller> tag with a plugin tag such as:

<gazebo reference="link_joint">
  <plugin name="gazebo_ros_force" plugin="libgazebo_ros_force.so">
    <alwaysOn>true</alwaysOn>
    <update>100</update>
    <updateRate>100.0</updateRate>
    <bodyName>link</bodyName>
    <topicName>force</topicName>
  </plugin>
</gazebo>

And here's what I do to get a current version of gazebo running with ros groovy:

We are running the the catkin_groovy gazebo version (branch):

sudo -E apt-get install build-essential libtinyxml-dev libtbb-dev libxml2-dev libqt4-dev pkg-config libprotoc-dev libfreeimage-dev libprotobuf-dev protobuf-compiler libboost-all-dev freeglut3-dev cmake libogre-dev libtar-dev libcurl4-openssl-dev libcegui-mk2-dev mercurial checkinstall git-core
cd
hg clone https://bitbucket.org/osrf/gazebo ~/gazebo -b catkin_groovy
mkdir ~/gazebo/build && cd ~/gazebo/build
source /opt/ros/groovy/setup.bash
cmake .. -DCMAKE_INSTALL_PREFIX=/usr/local
make # this takes some time ... to boost use -jx
sudo checkinstall -y --pkgname=Gazebo --pkgversion=1.X-YYYY # where X is the gazebo version and YYYY is the repository version, preferred over make install since it can be removed easily
sudo ldconfig
edit flag offensive delete link more

Comments

I tried this approach with the same result. How does Gazebo (1.5) load plugins through urdf now?

JezzaC gravatar imageJezzaC ( 2013-05-17 17:12:23 -0600 )edit

Hi, I have the same problem. Did you figure out how to fix it?

rguzman gravatar imagerguzman ( 2013-05-19 11:39:02 -0600 )edit
1

Here's an example: `https://bitbucket.org/osrf/drcsim/src/b4e76f22bc67/ros/atlas_description/urdf/atlas.gazebo?at=default`

nkoenig gravatar imagenkoenig ( 2013-05-21 18:42:19 -0600 )edit

As of gazebo 1.8.2, the syntax is `<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">` see example here: https://github.com/jhu-lcsr/ros_control_gazebo/blob/dd3f2990403223b77aaac091889478856f88def2/ros_control_gazebo_tests/models/rr_manipulator.urdf.xacro#L10

jbohren gravatar imagejbohren ( 2013-06-03 18:43:09 -0600 )edit
0

answered 2013-04-16 23:47:03 -0600

scpeters gravatar image

There's an error message related to the turnGravityOff tag, which is not in sdf 1.3. Try replacing it with a tag called gravity, (see sdf 1.3 documentation here).

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2013-04-15 00:09:46 -0600

Seen: 6,215 times

Last updated: Apr 16 '13