URDF Importer

The Unified Robot Description Format (URDF), is an XML format for representing a robot model in ROS. The URDF importer should be automatically loaded when Omniverse Isaac Sim opens and can be accessed from the Isaac Utils -> URDF Importer menu. If not, go to Window-> Extensions and enable omni.isaac.urdf.

User interface for URDF Importer

Configuration Options

Parser Settings

  • Merge Fixed Joints: Consolidate links that are connected by fixed joints, so that an articulation is only applied to joints that move.

  • 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.

  • 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.

Importer Settings

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

  • 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.

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

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

  • 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.

  • Make Default Prim: Makes the robot the default prim on the stage. This is useful when authoring scenes that use the robot as an asset, since only elements inside the default prim are carried over to the authored scene.

  • 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.

Note

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

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.

Import Franka Panda URDF From File

Go to the URDF Importer window, and click on the Select and Parse URDF button . In the file selection dialog box, navigate to the desired folder, and select the desired URDF file. For this example we will use the Franka panda_arm_hand.urdf file that is included in the Built in URDF Files that come with this extension.

Select URDF to Import

Inspection

Once the URDF is parsed, you can inspect its contents by clicking the Show Parsed Data button. The Tree-View list of links and joints can be expanded to show each imported item and their properties.

Parsed URDF data

Importing

Once all of the Parser and Importer settings are specified click the Import Robot To Stage button to add the robot to the stage.

Imported Franka

Visualizing Collision Meshes

Not all the rigid bodies need to have collision properties, and collision meshes are often a simplified mesh comparing to the visual ones. Therefore you may want to visualize the collision mesh for inspection.

To visualize collision in any viewport:

  • Select: the eyecon eye icon.

  • Select: Show by type.

  • Select: Physics Mesh.

  • Check: All.

../_images/isaac_physics_visualize_collision.png

The visualization of collision meshes uses the PhysX Visual Debugger (PVD) plugin. You can find more information on PVD itself here.

URDF Import Python API

See the API Documentation for usage information.

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 is

  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
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
# get handle to the Drive API for both wheels
left_wheel_drive = UsdPhysics.DriveAPI.Get(stage.GetPrimAtPath("/carter/chassis_link/left_wheel"), "angular")
right_wheel_drive = UsdPhysics.DriveAPI.Get(stage.GetPrimAtPath("/carter/chassis_link/right_wheel"), "angular")

# Set the velocity drive target in degrees/second
left_wheel_drive.GetTargetVelocityAttr().Set(150)
right_wheel_drive.GetTargetVelocityAttr().Set(150)

# Set the drive damping, which controls the strength of the velocity drive
left_wheel_drive.GetDampingAttr().Set(15000)
right_wheel_drive.GetDampingAttr().Set(15000)

# Set the drive stiffness, which controls the strength of the position drive
# In this case because we want to do velocity control this should be set to zero
left_wheel_drive.GetStiffnessAttr().Set(0)
right_wheel_drive.GetStiffnessAttr().Set(0)

Alternatively you can use the 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.