A Practical Approach to the NVIDIA Omniverse Robotics Simulation Toolkit, Part 2:

Exporting an High performance paint process robot

Spicytech
5 min readDec 9, 2023

Recipe : a set of instructions for preparing a particular dish, including a list of the ingredients required; e.g. Fluffy American pancakes.

The goal of this series of posts is to briefly describe workflows that I find very useful. For that, I am going to use a cooking recipe structure : ingredients, methodology and some comments as tips.

For this post I am going to describe how to add and verify from scratch a new robotic arm to Omniverse-Isaac

Preparation time : Less than 60 mins

Cooking time : Less than 10 mins

Brigade de cuisine : Sous-chef de partie / Saucier

Through the high-performance Lula library, the Motion Generation extension provides three abstract interfaces for adding robotic manipulation algorithms to Omniverse Isaac Sim :

The MotionPolicy is a collision aware algorithm that outputs actions on each frame to navigate a single robot to a single task-space target.

The PathPlanner class provides an interface that specifies the necessary functions that must be fulfilled in order to specify a path planning algorithm.

The KinematicsSolver has the capability of computing forward and inverse kinematics.

In general, Isaac simulates a robot as a Articulation. Addionally, in order to use the Motion Generation extensions, two files are necessary :

  • the Universal Robot Description File (URDF) and
  • a Robot Description File.

The Universal Robot Description File describes a robot as a set of links, and joints connecting the links together. So a typical robot description looks something like this :

<?xml version="1.0"?>
<robot name="pr2" xmlns="http://www.ros.org">
<link> ... </link>
<link> ... </link>
<link> ... </link>

<joint> .... </joint>
<joint> .... </joint>
<joint> .... </joint>
</robot>

The link element describes a rigid body with an inertia, visual features, and collision properties.

 <link name="my_link">
<inertial> ... </inertial>
<visual> ... </visual>
<collision> ... </collision>
</link>

Joints describes the kinematics and dynamics of the joint and also specifies the limits of the joint.

  <joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-3.1416" upper="3.1416" velocity="2.618"/>
</joint>

where

  • type, Specifies the type of joint (revolute, fixed, floating, etc)
  • parent, The name of the link that is the parent of this link in the robot tree structure.
  • child, The name of the link that is the child link.
  • origin, 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, Represents the x, y, z offset. All positions are specified in metres.
  • rpy, 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.
  • lower, An attribute specifying the lower joint limit (in radians for revolute joints, in metres for prismatic joints).
  • upper, An attribute specifying the upper joint limit (in radians for revolute joints, in metres for prismatic joints).
  • effort, An attribute for enforcing the maximum joint effort
  • velocity, An attribute for enforcing the maximum joint velocity

The Lula Robot Description File must distinguish each joint as either an Active Joint or a Fixed Joint. Anything marked as an Active Joint will be directly controlled, while anything marked as a Fixed Joint will be assumed to be fixed from the perspective of Lula algorithms. A key aspect of a Robot Description File is defining the robot c-space.

Dish

In a general way, in order to add a new robotic arm to Omniverse-Isaac two files must be created :

  1. the USD file that describes the new robot, and
  2. the Lula Robot Description File

The starting point is the URDF file along with the geometry corresponding to the robot in which you are interested.

For this post, I am going to work with the IRB 5400 robot belonging to ABB. The input files for this robot can be found in the following git repository.

Ingredients

The most important part of the URDF file is shown below.

<robot name="abb_irb5400" xmlns:xacro="http://ros.org/wiki/xacro">
...
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link_1"/>
...
</joint>
<joint name="joint2" type="revolute">
<parent link="link_1"/>
<child link="link_2"/>
...
</joint>
<joint name="joint3" type="revolute">
<parent link="link_2"/>
<child link="link_3"/>
...
</joint>
<joint name="joint4" type="revolute">
<parent link="link_3"/>
<child link="link_4"/>
...
</joint>
<joint name="joint5" type="revolute">
<parent link="link_4"/>
<child link="link_5"/>
...
</joint>
<joint name="joint5b" type="revolute">
<parent link="link_5"/>
<child link="link_5b"/>
...
</joint>
<joint name="joint6" type="revolute">
<parent link="link_5b"/>
<child link="link_6"/>
...
</joint>
<joint name="joint_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="tool0"/>
...
</joint>
</robot>

The following image shows the structure corresponding to the structure described in the URDF file. It can be seen that the robot has seven degrees of freedom.

The following tools will be used to create the robot

Additionally, I am going to use the LulaKinematicsSolver to validate that the robot has been created successfully.

Preparation

The following videos show in detail the steps I followed when exporting the IRB 5400 robot.

  1. Importing the URDF file
  2. Fixing defaul values
  3. Verifying the positions of the joints
  4. Creating the Lula Robot Descriptor file
  5. Loading the USD file
  6. Validation
  7. Final result

The following fragment codes were used in the videos.

from omni.isaac.core.utils.stage import add_reference_to_stage

ROOT_PATH = r"C:\Path\to\the\usd\file"
ROBOT_USD_PATH = ROOT_PATH + "\\" + "irb5400/irb5400.usd"

ROBOT_PRIM_PATH = "/ArticulationRoot"
add_reference_to_stage(ROBOT_USD_PATH, ROBOT_PRIM_PATH)
from omni.isaac.motion_generation import LulaKinematicsSolver

ROBOT_URDF_PATH = ROOT_PATH + "\\" + "irb5400.urdf"
ROBOT_YAML_PATH = ROOT_PATH + "\\" + "lula_robot_descriptor.yaml"

kinematics_solver = LulaKinematicsSolver(
robot_description_path=ROBOT_YAML_PATH,
urdf_path=ROBOT_URDF_PATH)
validFrames = kinematics_solver.get_all_frame_names()
validFrames.sort()

#'base,base_link,link_1,link_2,link_3,link_4,link_5,link_5b,link_6,tool0'
print(validFrames)

In the next parts of this series of posts I am going to show how to use the and Lula Trajectory Generator and its integration into the Omniverse User Interface and the timeline workflow.

Bon appétit!!

Appendix

from omni.isaac.core.utils.stage import add_reference_to_stage

ROOT_PATH = r"D:\CobottaPro900\Extension\exts\x.y\x\y\FilesMotoman"
ROBOT_USD_PATH = ROOT_PATH + "\\" + "mh5_env.usd"

ROBOT_PRIM_PATH = "/ArticulationRoot"
add_reference_to_stage(ROBOT_USD_PATH, ROBOT_PRIM_PATH)



from omni.isaac.motion_generation import LulaKinematicsSolver

ROBOT_URDF_PATH = ROOT_PATH + "\\" + "mh5.urdf"
ROBOT_YAML_PATH = ROOT_PATH + "\\" + "lula_robot_descriptor.yaml"

kinematics_solver = LulaKinematicsSolver(
robot_description_path=ROBOT_YAML_PATH,
urdf_path=ROBOT_URDF_PATH)
validFrames = kinematics_solver.get_all_frame_names()
validFrames.sort()

# ['base_link', 'link_b', 'link_l', 'link_r', 'link_s', 'link_t', 'link_u']
print(validFrames)

--

--

Spicytech

Experienced Software Developer | Always Eager to Learn