Problems while parsing <gazebo> URDF elements with Gazebo7 and ROS Jade
I use Gazebo 7 with ROS Jade for which
EDITED after ros-jade-gazebo7-ros-pkgs
cannot yet be installed (due to the dependency to ros-jade-gazebo7-plugins
which does not exist). Thus, I've cloned the jade-devel
branch of the gazebo_ros_pkgs
package in the catkin workspace and compiled it with catkin_make
.ros-jade-gazebo7-ros-pkgs
release: still the same behaviour.
Issue created on 2016/03/08
Check the details in the issue and follow the linked repository: https://bitbucket.org/osrf/sdformat/issues/113/parsing-from-urdf-to-sdf-does-not-handle
Update 2016/03/01
I've been investigated more on this problem and I've found out that it could be due to the new naming convention from Gazebo 6 on.** I've tried the example below with ROS Jade and Gazebo 5, 6 and 7 and it works only with the first one (which relies on sdformat2).
Using sdformat3 and sdformat4, <visual>
and <collision>
elements get augmented unique names when they are converted to SDF (which differ from those given in the URDF). Indeed, using <gazebo>
tags it is possible to add any element which will not end in <visual>
or <collision>
elements, e.g. <enable_wind>
or <velocity_decay>
which are directly children of the <link>
tag.
On the other hand, every element which has to be put inside <visual>
or <collision>
is completely ignored (without errors) from the parser. I think that it expects to use the URDF visual/collision names but they differ, e.g. visual_waist
and collision_waist
are the name in the URDF and the respectively SDF ones are waist_fixed_joint_lump__visual_waist_visual
and waist_fixed_joint_lump__collision_waist_collision
.
Should I report this bug on https://bitbucket.org/osrf/sdformat/overview ?
Example
I have made a simple example (download) to show that (at least with my configuration) elements inside <gazebo>
urdf tags are not correctly parsed by either spawn_model
or gz sdf -p
commands.
I followed this Gazebo tutorial: Using a URDF in Gazebo.
This is the package structure inside my caktkin workspace:
/robot: /robot_description: /urdf: robot.gazebo robot.urdf robot.xacro CMakeLists.txt package.xml /robot_gazebo: /launch: robot_world.launch /worlds: robot.world CMakeLists.txt package.xml
where robot.world
is a simple empty world and robot_world.launch
contains the URDF spawner:
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find robot_description)/urdf/robot.xacro'"/>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model robot -param robot_description"/>
and where the file in the /urdf
folder are as follow:
robot.xacro
<?xml version="1.0"?>
<robot name="robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- imports all Gazebo-customization elements, including Gazebo colors -->
<xacro:include filename="$(find robot_description)/urdf/robot.gazebo"/>
<!-- imports URDF robot model -->
<xacro:include filename="$(find robot_description)/urdf/robot.urdf"/>
</robot>
robot.urdf
<?xml version="1.0"?>
<robot name="robot">
<link name="pelvis">
<inertial>
<origin xyz="-1e-06 0.060095 -0.014315" rpy="0 0 0"/>
<mass value="2.468"/>
<inertia ixx="0.015171" ixy="0" ixz="0" iyy="0.022628" iyz="0" izz="0.018252"/>
</inertial>
<visual name="visual_pelvis">
<origin xyz="-4.5e-05 0.021 -0.01302" rpy="0 0 0"/>
<geometry>
<box size="0.25 0.162 0.217994"/>
</geometry>
</visual>
<collision name="collision_pelvis">
<origin xyz="-4.5e-05 0.021 -0.01302" rpy="0 0 0"/>
<geometry>
<box size="0.25 0.162 0.217994"/>
</geometry>
</collision>
</link>
<link name="waist">
<inertial>
<origin xyz="-0.001697 0.000427 0.011563" rpy="0 0 0"/>
<mass value="2.471"/>
<inertia ixx="0.013046" ixy="0" ixz="0" iyy="0.010016" iyz="0" izz="0.008802"/>
</inertial>
<visual name="visual_waist">
<origin xyz="0.004259 -0.022723 0.032313" rpy="0 0 0"/>
<geometry>
<box size="0.118392 0.1695 0.186073"/>
</geometry>
</visual>
<collision name="collision_waist">
<origin xyz="0.004259 -0.022723 0.032313" rpy="0 0 0"/>
<geometry>
<box size="0.118392 0.1695 0.186073"/>
</geometry>
</collision>
</link>
<joint name="pelvis_roll" type="revolute">
<origin xyz="-0.002 -0.067473 0.019" rpy="0 0 0"/>
<parent link="waist"/>
<child link="pelvis"/>
<axis xyz="0 0 1.0"/>
<dynamics damping="0.1" friction="0"/>
<limit lower="-0.25" upper="0.25" effort="100.0" velocity="10.0"/>
</joint>
</robot>
robot.gazebo
<?xml version="1.0"?>
<robot>
<gazebo>
<!-- ros_control plugin -->
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/robot</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<!-- link properties -->
<gazebo reference="pelvis">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>1.5</mu1>
<mu2>1.5</mu2>
<fdir1>0 0 1</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.00</minDepth>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="waist">
<material>Gazebo/Orange</material>
<collision>
<surface>
<friction>
<ode>
<mu>0.0</mu>
<mu2>0.0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
</gazebo>
<!-- joint properties -->
<gazebo reference="pelvis_roll">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
</robot>
In such a configuration, the only elements which are parsed by gazebo (or shown using gz sdf -p
) are the implicitSpringDamper
joint property and the gazebo_ros_control
plugin (actually there is also a /robot_control
directory with all the stuff necessary to control the robot but I don't report it for simplicity).
All the other elements for the links appear in Gazebo with the default values (indeed they are not parsed by the gz sdf -p
command). For example, not even materials are parsed...
Here are some screens of Gazebo:
Is it a dependency problem or something else?
Asked by alextoind on 2016-02-22 05:48:56 UTC
Comments
I ue the same notation as your in Gazebo6 adn ros indigo and I have no problem.
Asked by Brosseau.F on 2016-02-26 02:57:58 UTC
Thank you. I've just made some tests again after the realease (this morning) of
ros-jade-gazebo7-ros-pkgs
, but it has still the same behaviour...Asked by alextoind on 2016-02-26 03:54:08 UTC
Same Problem here on Gazebo6 and Ros Indigo
Asked by Franzisdrak on 2016-09-23 03:31:37 UTC
http://answers.gazebosim.org/question/15095/gazebo-contact-sensor-added-to-a-robot-link-in-urdf-file-is-not-working-as-expected/
Asked by dcconner on 2017-03-07 20:16:18 UTC
Sorry for not updating the post, I've created an issue which describes the same behavior exactly one year ago, but it is still not assigned. You can find it here: https://bitbucket.org/osrf/sdformat/issues/113/parsing-from-urdf-to-sdf-does-not-handle
Asked by alextoind on 2017-03-08 04:04:29 UTC
It works if the collision has no explicit name in URDF or if the name of the collision is
$LINKNAME_collision
. Any other names cause the tags to be ignored.Asked by peci1 on 2020-08-07 08:35:32 UTC