(Translated by https://www.hiragana.jp/)
GitHub - ami-iit/rod: The ultimate Python tool for RObot Descriptions processing.
Skip to content
/ rod Public

The ultimate Python tool for RObot Descriptions processing.

License

Notifications You must be signed in to change notification settings

ami-iit/rod

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

RObot Description processor

The ultimate Python tool for RObot Descriptions processing.

ROD is yet another library to operate on robot descriptions based on the SDFormat specification.

Why SDFormat?

Among the many existing robot description formats, SDFormat provides a well-defined and maintained versioned specification that controls the available fields and their content. Open Robotics already provides the C++ library gazebosim/sdformat with initial support of Python bindings. However, C++ dependencies in pure-Python projects are typically quite complicated to handle and maintain. Here ROD comes to rescue.

URDF, thanks to native ROS support, is historically the most popular robot description used by the community. The main problem of URDF is that it is not a specification, and developers of URDF descriptions might produce models and parsers that do not comply to any standard. Luckily, URDF models can be easily converted to SDF1. If the URDF model is not compliant, the process errors with clear messages. Furthermore, modern versions of the converter produce a SDF description with standardized pose semantics, that greatly simplifies the life of downstream developers that do not have to guess the reference frame or pose elements. Last but not least, the pose semantics also makes SDF aware of the concept of frame that URDF is missing.

Features

  • Out-of-the-box support for SDFormat specifications ≥ 1.10.
  • Serialization and deserialization support for SDF files.
  • In-memory layout based on dataclasses.
  • Syntax highlighting and auto-completion.
  • Programmatic creation of SDF files from Python APIs.
  • Transitive support for URDF through conversion to SDF.
  • Type validation of elements and attributes.
  • Automatic check of missing required elements.
  • High-performance serialization and deserialization using Fatal1ty/mashumaro.
  • Export in-memory model description to URDF.

Installation

Tip

ROD does not support out-of-the-box URDF files. URDF support is obtained by converting URDF files to SDF using the gz sdf command provided by sdformat and gz-tools. Ensure these tools are installed on your system if URDF support is needed (more information below).

Using conda (recommended)

Installing ROD using conda is the recommended way to obtain a complete installation with out-of-the-box support for both URDF and SDF descriptions:

conda install rod -c conda-forge

This will automatically install sdformat and gz-tools.

Using pip

You can install ROD from PyPI with pypa/pip, preferably in a virtual environment:

pip install rod[all]

If you need URDF support, follow the official instructions to install Gazebo Sim on your operating system, making sure to obtain sdformat ≥ 13.0 and gz-tools ≥ 2.0.

You don't need to install the entire Gazebo Sim suite. For example, on Ubuntu, you can only install the libsdformat13 gz-tools2 packages.

Examples

Serialize and deserialize SDF files
import pathlib

from rod import Sdf

# Supported SDF resources
sdf_resource_1 = "/path/to/file.sdf"
sdf_resource_2 = pathlib.Path(sdf_resource_1)
sdf_resource_3 = sdf_resource_2.read_text()

# Deserialize SDF resources
sdf_1 = Sdf.load(sdf=sdf_resource_1)
sdf_2 = Sdf.load(sdf=sdf_resource_2)
sdf_3 = Sdf.load(sdf=sdf_resource_3)

# Serialize in-memory Sdf object
print(sdf_3.serialize(pretty=True))
Create SDF models programmatically
from rod import Axis, Inertia, Inertial, Joint, Limit, Link, Model, Sdf, Xyz

sdf = Sdf(
    version="1.7",
    model=Model(
        name="my_model",
        link=[
            Link(name="base_link", inertial=Inertial(mass=1.0, inertia=Inertia())),
            Link(name="my_link", inertial=Inertial(mass=0.5, inertia=Inertia())),
        ],
        joint=Joint(
            name="base_to_my_link",
            type="revolute",
            parent="base_link",
            child="my_link",
            axis=Axis(xyz=Xyz(xyz=[0, 0, 1]), limit=Limit(lower=-3.13, upper=3.14)),
        ),
    ),
)

print(sdf.serialize(pretty=True))
<?xml version="1.0" encoding="utf-8"?>
<sdf version="1.7">
  <model name="my_model">
    <link name="base_link">
      <inertial>
        <mass>1.0</mass>
        <inertia>
          <ixx>1.0</ixx>
          <iyy>1.0</iyy>
          <izz>1.0</izz>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyz>0.0</iyz>
        </inertia>
      </inertial>
    </link>
    <link name="my_link">
      <inertial>
        <mass>0.5</mass>
        <inertia>
          <ixx>1.0</ixx>
          <iyy>1.0</iyy>
          <izz>1.0</izz>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyz>0.0</iyz>
        </inertia>
      </inertial>
    </link>
    <joint name="base_to_my_link" type="revolute">
      <parent>base_link</parent>
      <child>my_link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-3.13</lower>
          <upper>3.14</upper>
        </limit>
      </axis>
    </joint>
  </model>
</sdf>
Exporting SDF to URDF
# Generate first the 'sdf' object with the collapsed code
# of the section 'Create SDF models programmatically'.

from rod.urdf.exporter import UrdfExporter

urdf_string = UrdfExporter(pretty=True, gazebo_preserve_fixed_joints=True).to_urdf_string(
    sdf=sdf
)

print(urdf_string)
<?xml version="1.0" encoding="utf-8"?>
<robot name="my_model">
  <link name="base_link">
    <inertial>
      <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
      <mass value="1.0"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>
  <link name="my_link">
    <inertial>
      <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
      <mass value="0.5"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>
  <joint name="base_to_my_link" type="revolute">
    <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
    <parent link="base_link"/>
    <child link="my_link"/>
    <axis xyz="0 0 1"/>
    <limit effort="3.4028235e+38" velocity="3.4028235e+38" lower="-3.13" upper="3.14"/>
  </joint>
</robot>

Similar projects

Contributing

Pull requests are welcome. For major changes, please open an issue first to discuss what you would like to change.

Maintainers

@diegoferigo

License

BSD3

Footnotes

  1. Conversion can be done using the gz sdf command included in Gazebo Sim starting from Garden.