🤖
Introduction to ROS2 and Robotics
  • Introduction
  • ROS2
    • Index
    • IDE and CMake Setup
      • How to add additional include search path
    • ROS2 Building Blocks
      • ROS Workspace and Package Layout
      • Launch File
      • tf2
      • Quality of Service
      • Configurations
        • Rviz Configuration
      • Built-in Types
        • Built-in Message Type
    • ROS Architecture
      • Intra-process Communication
    • Navigation and Planning
      • Navigation Stack and Concepts
      • Navigation2 Implementation Overview
        • 🏗️Cost Map
        • Obstacle Avoidance and DWB Controller
      • DWB Controller
      • Page 5
    • How to launch the Nav2 stack
    • ROS2 Control
      • Online Resources
      • Overview of Codebase
    • 🍳Cookbook
      • Useful Commands
      • How to specify parameters
      • How to build the workspace
      • 🏗️How to publish message to a topic from command line?
      • How to inspect service and make a service call
      • How to properly terminate ROS and Gazebo
      • How to add and remove models in Gazebo simulation dynamically
      • 🚧How to spin nodes
    • 🛒Tutorials
      • Services and Communication between ROS2 and Gazebo
      • Subscription and Message Filters Demo
      • Executor and Spin Explained
      • Lifecycle Node Demo
      • Robotic Arm Demo
      • ⚒️Multiple Robotic Arms Simulation Demo
      • 🚧Introduction to xacro
    • Page
    • 🍺Tech Blog
      • Difference between URDF and SDF and how to convert
  • Gazebo
    • Index
    • Terminology
    • GUI
    • World Frame and Axis
    • Cookbook
    • Page 1
  • Programming in Robotics
    • C++
      • CMake
    • Python
    • Rust
  • Mathematics in Robotics
    • Linear Algebra
    • Matrix Properties
    • Probability
      • Expectation-Maximization Algorithm
    • Multivariable Function and Derivatives
  • Physics in Robotics
  • Control of Dynamic Systems
    • Dynamic Response and Transfer Function
    • Block Diagram
    • PID Controller
  • Robot Modeling and Control
    • Rotation and Homogeneous Transformation
  • Probabilistic Robotics
    • Bayes Filter
    • Kalman Filter
    • Particle Filter
    • Discrete Bayes Filter
    • Motion Model
    • Perception Model
    • Localization
    • SLAM
  • Miscellany
  • Concept Index
    • Quaternions
Powered by GitBook
On this page
  • Introduction
  • Related Readings
  • Difference in Syntax
  • Difference in transformation representation
  • Conversion from SDF to URDF
  • Parse SDF file
  • Convert to URDF Format
  • Adjust Model Directory
  • Adjust Transformation
  • Sample Code
  1. ROS2
  2. Tech Blog

Difference between URDF and SDF and how to convert

PreviousTech BlogNextGazebo

Last updated 1 year ago

Introduction

In this article, we discuss the differences betwee URFD and SDF, focusing on their syntax and transformation representation. Additionally, we demonstrate how to implement the conversion from SDF to URDF and provide a customizable sample code.

Related Readings

Difference in Syntax

The primary distinction between URDF and SDF lies in their syntax. You can find more details in the official format specifications online. Here, we illustrate with examples to showcase the apparent differences. In URDF, attributes are typically embedded within a tag as fields, such as <inertia ixx="..."/>. Conversely, SDF expresses the same information through nested tags, like <inertia><ixx>...</ixx></inertia>.

Example of URDF

<link name="base_link">
    <visual>
    <origin xyz="0 0 0.05" rpy="0 0 0"/>
    <geometry>
        <box size="2.5 1.5 0.1" />
    </geometry>
    <material name="green">
        <color rgba="0.2 1 0.2 1"/>
    </material>
    </visual>

    <collision>
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <geometry>
            <box size="2.5 1.5 0.1" />
        </geometry>
    </collision>

    <inertial>
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <mass value="12" />
        <inertia ixx="2.26" ixy="0.0" ixz="0.0" iyy="6.26" iyz="0.0" izz="8.5" />
    </inertial>
</link>

<joint name="slider_joint" type="prismatic">
    <origin xyz="-1.25 0 0.1" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="slider_link"/>
    <axis xyz="1 0 0"/>
    <limit lower="0" upper="2" velocity="100" effort="100"/> 
</joint>

Example of SDF

<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>
  <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>
  <visual name='visual'>
    <geometry>
      <mesh>
        <uri>model://ur10/meshes/base.dae</uri>
      </mesh>
    </geometry>
  </visual>
</link>

<joint name='wrist_1_wrist_2' type='revolute'>
  <child>wrist_2</child>
  <parent>wrist_1</parent>
  <axis>
    <xyz>3.58979e-09 0 -1</xyz>
    <limit>
      <lower>-6.28319</lower>
      <upper>6.28319</upper>
      <effort>54</effort>
      <velocity>3.2</velocity>
    </limit>
    <use_parent_model_frame>1</use_parent_model_frame>
  </axis>
</joint>

Difference in transformation representation

A key difference between URDF and SDF lies in how transformations are represented. In URDF, transformations are specified with in the joint element, whereas in SDF, they are defined separated in the parent and child link elements. For instance:

<!-- URDF -->
<joint name="slider_joint" type="prismatic">
    <parent link="base_link"/>
    <child link="slider_link"/>
    <origin xyz="-1.25 0 0.1" rpy="0 0 0"/>
</joint>

<!-- SDF -->
<link name="base_link">
    <pose>0 0 0 0 0 0</pose>
</link>

<link name="slider_link">
    <pose>some values here</pose>
</link>

<joint name="slider_joint" type="prismatic">
    <parent>base_link</parent>
    <child>slider_link</child>
</joint>

It's important to note that during the conversion from SDF to URDF, values for the pose tag in the child link are not directly transferred. This is because the representation of transformations differ significantly between the two formats, making the process more complex than a straightforward copy of tag values.

(optional: defaults to identity if not specified)

This is the transform from the parent link to the child link. The joint is located at the origin of the child link, as shown in the figure above.

xyz (optional: defaults to zero vector): Represents the x, y, z offset. All positions are specified in metres.

rpy (optional: defaults to zero vector): Represents the rotation around fixed axis: first roll around x, then pitch around y and finally yaw around z. All angles are specified in radians.

Element Required: 0 Type: pose Default: 0 0 0 0 0 0 Description: A pose (translation, rotation) expressed in the frame named by @relative_to. The first three components (x, y, z) represent the position of the element's origin (in the @relative_to frame). The rotation component represents the orientation of the element as either a sequence of Euler rotations (r, p, y), see http://sdformat.org/tutorials?tut=specify_pose, or as a quaternion (x, y, z, w), where w is the real component.

relative_to Attribute Required: 0 Type: string Default: Description:If specified, this pose is expressed in the named frame. The named frame must be declared within the same scope (world/model) as the element that has its pose specified by this tag. If missing, the pose is expressed in the frame of the parent XML element of the element that contains the pose. For exceptions to this rule and more details on the default behavior, see http://sdformat.org/tutorials?tut=pose_frame_semantics. Note that @relative_to merely affects an element's initial pose and does not affect the element's dynamic movement thereafter. New in v1.8: @relative_to may use frames of nested scopes. In this case, the frame is specified using :: as delimiter to define the scope of the frame, e.g. nested_model_A::nested_model_B::awesome_frame.

This implies that the transformation described in the pose tag of the child link may be based on the world frame (by default) or a frame specified in the relative_to attribute, which differ from the parent frame.

When you download an SDF file, it often uses the default mode of the pose tag, where link transformations are expressed in the world frame. Directly copying the the child link's pose value from an SDF file to the origin tag of a URDF joint element may lead to unexpected results. The below screenshot illustrates this effect. We also replicate this in Three.js, using the Group concept to verify the behavior.

Another tag that has similar nuance is axis. For simplicity, we will not dive into the details in this article.

Conversion from SDF to URDF

Since Gazebo can use URDF files directly, conversion from URDF to SDF is typically unnecessary. However, when downloading the robot models from the internet, which are often in the SDF format, converting them to URDF becomes essential. This section will outline the steps in this conversion process.

Parse SDF file

The first step is to parse the SDF file and create an in-memory representation. An XML parser library such as ElementTree in python can do the job.

Convert to URDF Format

Follow the URDF specification and convert the in-memory representation into the URDF format. This step is a standard serialization process.

Adjust Model Directory

For SDF files that use mesh files, it's often necessary to modify the model path. This is because ROS2 and Gazebo locate model files differently. In URDF, mesh file locations are specified as follows:

<mesh filename="package://$(find <pkg-with-resource>)/robot_description/meshes/base_link.DAE"/>

where as in SDF, we use the following form:

<mesh>
    <uri>model://ur10/meshes/base.dae</uri>
</mesh>

The key distinction between the two formats lies in their path references: URDF uses an absolute path, whereas SDF employs a relative path that depends on an environment variable that configure the model search directory. To standardize the path, we can set this environment variable to the directory of the package that contains the model resources. In Gazebo Fortress, the relevant variable is IGN_GAZEBO_RESOURCE_PATH. This adjustment can be implemented in the python launch file. For instance,

os.environ['IGN_GAZEBO_RESOURCE_PATH'] = get_package_share_directory('<pkg-with-resource>')

Adjust Transformation

As discussed earlier, converting transformation of child links from the world frame to the parent frame may be necessary. The pose element in SDF takes the form x y z r p y and in both pose and origin tags, the xyz represents to the translation part of the transformation and the rpy attribute denote rotation. Recall that the homogeneous transformation is represented as follows:

H=[Rd01]H=\begin{bmatrix}R & d \\0 & 1 \\ \end{bmatrix}H=[R0​d1​]

Suppose the pose of link represents the transformation in the world frame. Consider a joint with parent link and the child link. This scenario involves three frames:

  • world frame

  • parent frame

  • child frame

and three transformations:

  • H10H_1^0H10​: transformation of parent frame expressed in the world frame

  • H20H_2^0H20​: transformation of child frame expressed in the world frame

  • H21H_2^1H21​: transformation of the child frame expressed in the parent frame

The first two transformation are inputs as they are given in the SDF file; the third transformation is the output because that's the information we need to put in the joint tag in the URDF file.

The conversion is given the formula below:

H21=(H10)−1H20H_2^1 = (H_1^0)^{-1}H_2^0H21​=(H10​)−1H20​

and the inverse of the homogeneous transformations is given as:

H−1=[RT−RTd01]H^{-1} = \begin{bmatrix} R^T & -R^Td \\ 0 & 1 \\ \end{bmatrix}H−1=[RT0​−RTd1​]

The python code below implements the conversion using scipy:

import numpy as np
from scipy.spatial.transform import Rotation as R

def compute_relative_transformation(rot_parent, d_parent, rot_child, d_child):
    """
    Computes the relative transformation for the child frame expressed in parent frame.

    :param rot_parent: The rotation matrix of the parent frame expressed in the world frame.
    :param d_parent: The translation vector of the parent frame expressed in the world frame.
    :param rot_child: The rotation matrix of the child frame expressed in the world frame.
    :param d_child: The translation vector of the child frame expressed in the world frame.

    :return: The relative transformation of the child frame express in the parent frame.
             The translation part is a 3d vector and the rotation is also a 3d vector in rpy format.
    """

    H_p_inv = np.zeros((4,4))
    H_p_inv[:3, :3] = rot_parent.T
    H_p_inv[:3, -1] = -np.matmul(rot_parent.T, d_parent)
    H_p_inv[3, 3] = 1

    H_c = np.zeros((4, 4))
    H_c[:3, :3] = rot_child
    H_c[:3, -1] = d_child
    H_c[-1, -1] = 1

    H_relative = np.matmul(H_p_inv, H_c)

    translation = H_relative[:3, -1]
    rotation_mat = H_relative[:3, :3]
    rotation = R.from_matrix(rotation_mat).as_euler("xyz", degrees=False)
    return translation, rotation
    

Sample Code

©2023 - 2024 all rights reserved

The specification of the transformation in URDF is straightforward. According to the :

It's important to note that the transformations in URDF are always relative (i.e. from the parent link frame to the child link frame), whereas in SDF, they are more nuanced. According to the :

We created a that illustrates the steps mentioned in this article, which is not suitable for production usage.

🍺
URDF XML Specification
link
joint
SDF Pose Frame Semantics Tutorial
xacro documentation
ROS xacro tutorial
gz_ros2_control demo
Tutorial: Using a URDF in Gazebo
Mesh element in URDF example
specification document
SDF document
python package