π§Introduction to xacro
The first challenge is model description. ROS2 and Ignition Gazebo use different formats for robot description. ROS2 uses URDF and Gazebo uses SDF. Many solutions exist to deal with this issue. One can keep both URDF and SDF files at cost of maintaining two different files that need to be in sync. If we modify one of the files, the other one needs to be updated accordingly. Another approach is to use conversion tools. However, this dependency on external tools can be a blocker when we run into corner cases which are not covered by the tools.
In this tutorial, we will show how to leverage xacro to generate both URDF and SDF files from a single source.
We will walk you through how to create xacro file to describe our robot.
First, create the name space and give our robot a name.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="ur10-my-robot">
...
</robot>
For this source file is used to generate two different files, we need a way to distinguish the two cases. This can be achieved by introducing a sim_gazebo
flag:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="ur10-my-robot">
<xacro:arg name="sim_gazebo" default="false" />
...
</robot>
Let's add a link. A typical link definition in URDF files looks similar to the one below:
<link name="my_link">
<inertial>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="1 1 1" />
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="1" length="0.5"/>
<!-- or if we need to refer to a DAE file
<mesh filename="package://robot_description/meshes/base_link_simple.DAE"/>
-->
</geometry>
</collision>
</link>
And a typical link definition in SDF looks like the following:
<link name='base'>
<inertial>
<mass>4</mass>
<inertia>
<ixx>0.00610633</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00610633</iyy>
<iyz>0</iyz>
<izz>0.01125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<mesh>
<uri>model://ur10/meshes/base.dae</uri>
</mesh>
</geometry>
</visual>
<collision name='collision'>
<pose>0 0 0.019 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.075</radius>
<length>0.038</length>
</cylinder>
</geometry>
</collision>
</link>
It's unfortunate that the syntax is similar but not exactly the same. To deal with different format, we will parameterize these blocks and leverage the macro.
Last updated