URDF Importer

About

Starting from the Isaac Sim 2023.1.0 release, the URDF importer has been open-sourced. Source code and information for contributing can be found at our github repo.

The URDF Importer Extension is used to import URDF representations of robots. Unified Robot Description Format (URDF), is an XML format for representing a robot model in ROS.

To access this Extension, go to the top menu bar and click Isaac Utils > Workflows > URDF Importer.

This extension is enabled by default. If it is ever disabled, it can be re-enabled from the Extension Manager by searching for omni.importer.urdf.

Overview of URDF Importer Extension

Note

To import a xacro document, first convert it to urdf using rosrun xacro xacro -o <output_name>.urdf <input_file>.urdf.xacro for robot descriptions already in your catkin workspace. For more information, see http://wiki.ros.org/xacro

Conventions

Warning

Special characters in link or joint names are not supported and will be replaced with an underscore. In the event that the name starts with an underscore due to the replacement, an a is pre-pended. It is recommended to make these name changes in the urdf directly.

See the Isaac Sim Conventions documentation for a complete list of Omniverse Isaac Sim conventions.

API Documentation

See the Python API Documentation for usage information.

User Interface

User interface for URDF Importer

Ref #

Item

Description

1

Information Panel

This panel has useful information about this extension.

2

Import Options Panel

This panel has utility functions for testing the gains being set for the Articulation. See Import Options below for full details.

3

Import Panel

This panel holds the source path, destination path, and import button.

  • Input File

Path to URDF to Import.

  • Output Directory

Path to save converted URDF.

  • Import

Button to import and save out the URDF as USD.

Import Options

  • Merge Fixed Joints: Consolidate links that are connected by fixed joints, so that an articulation is only applied to joints that move. Merged frames will still appear as children of the parent Frame they were merged to.

  • Fix Base Link: When checked, the robot will have its base fixed where it’s placed in world coordinates.

  • Import Inertia Tensor: Check to load inertia from urdf directly. If the urdf does not specify an inertia tensor, identity will be used and scaled by the scaling factor. If unchecked, Physx will compute it automatically. non-diagonal Inertia matrix components will be used to compute a principal axis representation along with a diagonal.

  • Stage Units Per Meter: Omniverse Kit default length unit is centimeters. Here you can set the scaling factor to match the unit used in your URDF. Currently, the URDF importer only supports uniform global scaling. Applying different scaling for different axes and specific mesh parts (i.e. using the scale parameter under the URDF mesh label) will be available in future releases. If you have a scale parameter in your URDF, you may need to manually adjust the other values in the URDF so that all parameters are in the same unit.

  • Link Density: If a link does not have a given mass, uses this density (in Kg/m^3) to compute mass based on link volume. A value of 0.0 can be used to tell the physics engine to automatically compute density as well.

  • Joint Drive Type: Default Joint drive type, Values can be None, Position, and Velocity.

  • Joint Drive Strength: The drive strength is the joint stiffness for position drive, or damping for velocity driven joints.

  • Joint Position Drive Damping: If the drive type is set to position this is the default damping value used.

  • Clear Stage: When checked, cleans the stage before loading the new URDF, otherwise loads it on current open stage at position (0,0,0)

  • Normals Subdivision: Mesh Normal subdivision scheme. If the imported mesh contains authored Normals, select none to avoid overriding them.

  • Convex Decomposition: If Checked, the collision object will be made a set of Convex meshes to better match the visual asset. Otherwise a convex hull will be used.

  • Self Collision: Enables self collision between adjacent links. It may cause instability if the collision meshes are intersecting at the joint.

  • Collision From Visuals: If Collisions are not authored as their own mesh, check this to use the visual meshes to define the colliders.

  • Create Physics Scene: Creates a default physics scene on the stage. Because this physics scene is created outside of the robot asset, it won’t be loaded into other scenes composed with the robot asset.

  • Create Instanceable Asset: Select this to create an asset that has instanceable Meshes. This is useful for scenes that contain multiple instances of the same robot (e.g. Reinforcement Learning tasks).

  • Output Directory: The destination of the imported asset. it will create a folder structure with the robot asset and all textures used for its rendering. You must have write access to this directory.

Note

It is recommended to set Self Collision to false unless you are certain that links on the robot are not self colliding

Note

Known Issue: If more than one asset in URDF contains the same material name, only one material will be created, regardless if the parameters in the material are different (e.g two meshes have materials with the name “material”, one is blue and the other is red. both meshes will be either red or blue.). This also applies for textured materials.

Note

You must have write access to the output directory used for import, it will default to the current open stage, change this as necessary.

Robot Properties

There might be many properties you want to tune on your robot. These properties can be spread across many different Schemas and APIs.

The general steps of getting and setting a parameter are:

  1. Find which API is the parameter under. Most common ones can be found in the Pixar USD API.

  2. Get the prim handle that the API is applied to. For example, Articulation and Drive APIs are applied to joints, and MassAPIs are applied to the rigid bodies.

  3. Get the handle to the API. From there on, you can Get or Set the attributes associated with that API.

For example, if we want to set the wheel’s drive velocity and the actuators’ stiffness, we need to find the DriveAPI:

 1# get handle to the Drive API for both wheels
 2left_wheel_drive = UsdPhysics.DriveAPI.Get(stage.GetPrimAtPath("/carter/chassis_link/left_wheel"), "angular")
 3right_wheel_drive = UsdPhysics.DriveAPI.Get(stage.GetPrimAtPath("/carter/chassis_link/right_wheel"), "angular")
 4
 5# Set the velocity drive target in degrees/second
 6left_wheel_drive.GetTargetVelocityAttr().Set(150)
 7right_wheel_drive.GetTargetVelocityAttr().Set(150)
 8
 9# Set the drive damping, which controls the strength of the velocity drive
10left_wheel_drive.GetDampingAttr().Set(15000)
11right_wheel_drive.GetDampingAttr().Set(15000)
12
13# Set the drive stiffness, which controls the strength of the position drive
14# In this case because we want to do velocity control this should be set to zero
15left_wheel_drive.GetStiffnessAttr().Set(0)
16right_wheel_drive.GetStiffnessAttr().Set(0)

Alternatively you can use the Omniverse Commands Tool to change a value in the UI and get the associated Omniverse command that changes the property.

Note

  • The drive stiffness parameter should be set when using position control on a joint drive.

  • The drive damping parameter should be set when using velocity control on a joint drive.

  • A combination of setting stiffness and damping on a drive will result in both targets being applied, this can be useful in position control to reduce vibrations.

Tutorials & Examples

The following tutorials and examples showcase how to best use this extension:

Tutorials

Examples

  • Carter Example: Isaac Examples > Import Robot > Carter URDF

  • Franka Example: Isaac Examples > Import Robot > Franka URDF

  • Kaya Example: Isaac Examples > Import Robot > Kaya URDF

  • UR10 Example: Isaac Examples > Import Robot > UR10 URDF

Note

For these examples, please wait for materials to get loaded. You can track progress on the bottom right corner of the UI.

Carter URDF Example

To run the Example:

  1. Go to the top menu bar and click Isaac Examples > Import Robots > Carter URDF.

  2. Press the Load Robot button to import the URDF into the stage, add a ground plane, add a light, and a physics scene.

  3. Press the Configure Drives button to configure the joint drives and allow the rear pivot to spin freely.

  4. Press the Open Source Code button to view the source code. The source code illustrates how to import and integrate the robot using the Python API.

  5. Press the PLAY button to begin simulating.

  6. Press the Move to Pose button to make the robot drive forward.

Carter URDF Sample

Franka URDF Example

  1. Go to the top menu bar and click Isaac Examples > Import Robots > Franka URDF.

  2. Press the Load Robot button to import the URDF into the stage, add a ground plane, add a light, and a physics scene.

  3. Press the Configure Drives button to configure the joint drives. This sets each drive stiffness and damping value.

  4. Press the Open Source Code button to view the source code. The source code illustrates how to import and integrate the robot using the Python API.

  5. Press the PLAY button to begin simulating.

  6. Press the Move to Pose button to make the robot move to a home/rest position.

Franka URDF Sample

Kaya URDF Example

  1. Go to the top menu bar and click Isaac Examples > Import Robots > Kaya URDF.

  2. Press the Load Robot button to import the URDF into the stage, add a ground plane, add a light, and a physics scene.

  3. Press the Configure Drives button to configure the joint drives. This sets the drive stiffness and damping value of each wheel, sets all of its rollers as freely rotating.

  4. Press the Open Source Code button to view the source code. The source code illustrates how to import and integrate the robot using the Python API.

  5. Press the PLAY button to begin simulating.

  6. Press the Move to Pose button to make the robot rotate in place.

Kaya URDF Sample

UR10 URDF Example

  1. Go to the top menu bar and click Isaac Examples > Import Robots > Kaya URDF.

  2. Press the Load Robot button to import the URDF into the stage, add a ground plane, add a light, and a physics scene.

  3. Press the Configure Drives button to configure the joint drives. This sets each drive stiffness and damping value.

  4. Press the Open Source Code button to view the source code. The source code illustrates how to import and integrate the robot using the Python API.

  5. Press the PLAY button to begin simulating.

  6. Press the Move to Pose button to make the robot move to a home/rest position.

UR10 URDF Sample