URDF Importer

The Unified Robot Description Format (URDF), is an XML format for representing a robot model in ROS. An URDF importer should be automatically loaded when kit opens, and its tab is at the bottom of the screen. If not, go to Window-> Extension Manager and enable omni.isaac.urdf.

Sample Imports

We provide URDFs for a few robots to get you started. Go to Isaac Robotics -> URDF, you can load a Franka, a Kaya, or a Carter robot.

Note

Please wait for materials to get loaded. You can track progress on the bottom right corner of UI. You may also need to zoom out to see the robot.

To interact with the loaded URDF, press play, and in the stage window select a joint, such as panda/panda_link1/panda_joint2. In the details panel modify the drive:angular:target or drive:linear:target value to see the joint move.

Import Custom URDF

Inside the URDF tab, click on Load URDF. In the appeared dialog box, navigate to the desired folder. In the bottom right dropdown select All Files (*.*) and select desired file.

../_images/isaac_main_urdf_import.jpg

Configuration Options

Clean Stage

Load URDF onto existing stage, or check the box and clean the stage before loading the new URDF.

Merge Fixed Joints

Consolidating links that are connected by fixed joints, so that articulation is only applied to joints that moves.

Enable Convex Decomposition

Decompose a convex mesh into smaller pieces to better fit the visual mesh.

Force Z Up

Kit’s default coordinate system has Y as the up-axis. URDFs usually assumes Z is up. This option force Z to be up in kit.

Scaling Factor

Kit’s 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.

Import Inertia Tensor

Check to load inertia from urdf directly. If the urdf does not specify inertia tensor, identity will be used and scaled by the scaling factor. If unchecked, physx will compute it automatically.

Visualizing Collision Meshes

If your URDF reference different mesh models for visual and collision meshes, you may want to visualize the collision mesh for inspection. We will use the PhysX Debugger for this.

First, stop the editor and let the robot go back to default position. Then go to Physics->PhysX Debug Window, Under Physics debug visualization category, open up the dropdown list for Show collision shapes, and select All. The collision meshes will now be outlined in purple.

../_images/isaac_main_urdf_collision.gif

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

Python API

Here are some useful Python API snippets that will get you started with loading your robot into kit and configuring it. Versions of the code below can be found in the samples’ scripts. This can also run directly inside Kit’s Script Editor.

Loading the URDF

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
    import carb
    import os
    import omni
    from pxr import PhysicsSchema, Gf, PhysicsSchemaTools

    # enable urdf importer extension
    from omni.isaac.urdf import _urdf

    # acquire urdf interface
    _urdf = _urdf.acquire_urdf_interface()

    # setting up import configuration:
    import_config = _urdf.ImportConfig()
    import_config.merge_fixed_joints = False
    import_config.distance_scale = 10
    import_config.enable_convex_decomp = False
    import_config.force_z_up = True

    # import URDF
    path = "data/urdf/robots/carter/urdf/carter.urdf"
    urdf_path = os.path.abspath(carb.tokens.get_tokens_interface().resolve("${app}/../" + path))
    _urdf.import_urdf(urdf_path, import_config)

Staging the Environment

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
    # get stage handle
    stage = omni.usd.get_context().get_stage()

    # enable phsyics
    scene = PhysicsSchema.PhysicsScene.Define(stage, Sdf.Path("/physicsScene"))

    # set gravity
    scene.CreateGravityAttr().Set(Gf.Vec3f(0.0, 0.0, -981.0))

    # add ground plane
    PhysicsSchemaTools.addGroundPlane(stage, "/groundPlane", "Z", 1500.0, Gf.Vec3f(-50), Gf.Vec3f(0.5))

    # add lighting
    distantLight = UsdLux.DistantLight.Define(stage, Sdf.Path("/DistantLight"))
    distantLight.CreateIntensityAttr(500)

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 Help->Python scripting manual->Scripting API->pxr package->PhysicsSchema module or UsdGeom module.

  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, to make sure Carter, a segway, is not fixed in place, we need to make sure FixBase Attribute is set to False.

1
2
3
4
5
6
    # get handle to the root link of the robot
    carter_prim = stage.GetPrimAtPath("/carter")
    # get handle to the articulation API
    physicsArticulationAPI = PhysicsSchema.ArticulationAPI.Get(stage, carter_prim.GetPath())
    # unfix articulation root
    physicsArticulationAPI.GetFixBaseAttr().Set(False)

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 = PhysicsSchema.DriveAPI.Get(stage.GetPrimAtPath("/carter/chassis_link/left_wheel"), "angular")
    right_wheel_drive = PhysicsSchema.DriveAPI.Get(
        stage.GetPrimAtPath("/carter/chassis_link/right_wheel"), "angular"
    )

    left_wheel_drive.GetTargetTypeAttr().Set('velocity')
    right_wheel_drive.GetTargetTypeAttr().Set('velocity')

    # if the attribute hasn't been used yet, you can create it and set it at the same time:
    left_wheel_drive.CreateTargetAttr(2.5)
    right_wheel_drive.CreateTargetAttr(2.5)

    # set stiffness of the joint
    left_wheel_drive.GetStiffnessAttr().Set(0.0)
    right_wheel_drive.GetStiffnessAttr().Set(0.0)

Extending a Robot

After Loading a base robot, it is possible to create alternate versions of the robot using the same base asset. For example, the UR10 base asset was loaded from the example ur10 urdf, which contains no end effector. And then two derived versions are shown, with a short surface gripper, and a longer surface gripper. Changes made in the base assets this way will impact all assets which contain it as reference.

Example

These are the steps to create an extended robot model:

  1. Create a new empty scenario. If any world prim is created, delete it.

  2. Locate the base robot in the contents path, and drag it onto the scene. at the position (0,0,0). In the video example we are using the UR10 robot.

  3. Set the Robot root as the default Prim by Right-clicking at the robot root and selecting Set Default Prim.

  4. Create an XForm inside the end robot’s effector link and set its pose to (0,0,0). In the example we will place it under wrist_3_link, and name the new Xform ee_link.

  5. Move the XForm outside of the end effector link and inside the robot link.

  6. Make the new XForm instanceable.

  7. Under the PhysX Properties tab, Add the Physics API Prim component.

  8. Locate the End Effector Asset and drag it into the newly created Xform.

  9. In the Physics menu, select Physics->Joint Atrributes->Fixed.

  10. Select the robot link, and the newly created Xform, and on the Physixs menu select Physics->Add->Joint->Between Selected. This will create a fixed joint between the new robot’s end effctor link and the newly created link.

  11. Make any final changes to the asset, and save the file.