Tutorial: Import URDF#
Learning Objectives#
This tutorial shows how to import a URDF and convert it to a USD in NVIDIA Isaac Sim. After this tutorial, you can use URDF files in your pipeline while using NVIDIA Isaac Sim.
10-15 Minutes Tutorial
Getting Started#
Prerequisites
Review the Getting Started Tutorials prior to beginning this tutorial.
Check the URDF Importer Extension for more details on the extension.
Let’s begin by importing a Franka Panda URDF from the Built in URDF files that come with the extension.
Enable the isaacsim.asset.importer.urdf extension in NVIDIA Isaac Sim if it is not automatically loaded by going to Window-> Extensions and enable isaacsim.asset.importer.urdf.
- In this example, we will import the panda_arm_hand.urdf that is included in the URDF importer extension. The easiest way to find it is:
Click on the file icon beside AUTOLOAD to find the isaacsim.asset.importer.urdf extension
Navigate to
/data/urdf/robots/franka_description/robots
and findpanda_arm_hand.urdf
, and copy this path
Accesses the URDF extension by going to the File > Import, and select an URDF file you wish to import. In this case, paste the path above to the navigation bar and left-click on panda_arm_hand.urdf
Specify the settings you want to use to import Franka with:
Set USD Ouptut to your desired output location for the USD
Select Static Base and leave Default Density empty
Refer to urdf importer Robot Properties for Joints and Drive instructions. In this tutorial, we can use the default values.
Select Allow Self-Collision for the Colliders section and leave everything else as default
Note
You must have write access to the output directory used for import, it will default to the same directory as your URDF
Click the Import button to add the robot to the stage.
#. Visualize the collision meshes, not all the rigid bodies need to have collision properties, and collision meshes are often a simplified mesh compared to the visual ones. Therefore you may want to visualize the collision mesh for inspection. To visualize collision in any viewport:
Note
If you are importing a mobile robot, you may need to change the following settings:
Select Moveable Base
Set the joint drive type to Velocity drive for the velocity controlled joints (i.e. wheels), and Position for the position controlled joints (i.e. steering joint)
Set the Joint Drive Strength to the desired level. Note that this will be imported as the joint’s damping parameter. Joint stiffness are always set to zero in velocity drive mode.
Note
If you are importing a torque controlled mobile robot such as a quadruped:
Select Moveable Base
Set the joint drive type to None drive for the torque controlled joints (i.e. legs), and Position or Velocity for the position or velocity controlled joints
Set the Joint Drive Strength to the desired level. For the torque controlled drives, Stiffness and damping have no effect and will be imported as zero.
First activate Windows > Examples > Robotics Examples which will open the Robotics Examples
tab at the bottom dock.
Note
For these examples, wait for materials to get loaded. You can track progress on the bottom right corner of the UI.
There are Four examples available in the Import Robots section:
Nova Carter URDF
Franka URDF
Kaya URDF
UR10 URDF
Each one of them contains an individual import configuration and post import setup in code, but overall the usage would be similar:
Go to the Robotics Examples tab and navigate to Import Robots > <Robot> URDF.
Press the Load Robot button to import the URDF into the stage, add a ground plane, add a light, and a physics scene.
Press the Configure Drives button to configure the joint drives. This sets each drive stiffness and damping value.
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.
Press the PLAY button to begin simulating.
Press the Move to Pose button to make the robot move to a home/rest position.
Let’s do the exact same things as we done through the Import window but with Python scripting instead. We will then use the imported robot with one of the tasks defined under isaacsim.robot.manipulators.examples.franka extension to follow a target in the stage.
- Let’s begin by opening the Hello World example.
Go to the top Menu Bar and Click Window > Examples > Robotics Examples.
In the Robotics Examples tab at the bottom, select General > Hello World
The window for the Hello World example extension should now be visible in the workspace.
Click the Open Source Code button to launch the source code for editing in Visual Studio Code.
Edit the hello_world.py file as shown below.
1from isaacsim.examples.interactive.base_sample import BaseSample
2from isaacsim.core.utils.extensions import get_extension_path_from_name
3from isaacsim.asset.importer.urdf import _urdf
4from isaacsim.robot.manipulators.examples.franka.controllers.rmpflow_controller import RMPFlowController
5from isaacsim.robot.manipulators.examples.franka.tasks import FollowTarget
6import omni.kit.commands
7import omni.usd
8
9class HelloWorld(BaseSample):
10 def __init__(self) -> None:
11 super().__init__()
12 return
13
14 def setup_scene(self):
15 # Get the world object to set up the simulation environment
16 world = self.get_world()
17
18 # Add a default ground plane to the scene for the robot to interact with
19 world.scene.add_default_ground_plane()
20
21 # Acquire the URDF extension interface for parsing and importing URDF files
22 urdf_interface = _urdf.acquire_urdf_interface()
23
24 # Configure the settings for importing the URDF file
25 import_config = _urdf.ImportConfig()
26 import_config.convex_decomp = False # Disable convex decomposition for simplicity
27 import_config.fix_base = True # Fix the base of the robot to the ground
28 import_config.make_default_prim = True # Make the robot the default prim in the scene
29 import_config.self_collision = False # Disable self-collision for performance
30 import_config.distance_scale = 1 # Set distance scale for the robot
31 import_config.density = 0.0 # Set density to 0 (use default values)
32
33 # Retrieve the path of the URDF file from the extension
34 extension_path = get_extension_path_from_name("isaacsim.asset.importer.urdf")
35 root_path = extension_path + "/data/urdf/robots/franka_description/robots"
36 file_name = "panda_arm_hand.urdf"
37
38 # Parse the robot's URDF file to generate a robot model
39 result, robot_model = omni.kit.commands.execute(
40 "URDFParseFile",
41 urdf_path="{}/{}".format(root_path, file_name),
42 import_config=import_config
43 )
44
45 # Update the joint drive parameters for better stiffness and damping
46 for joint in robot_model.joints:
47 robot_model.joints[joint].drive.strength = 1047.19751 # High stiffness value
48 robot_model.joints[joint].drive.damping = 52.35988 # Moderate damping value
49
50 # Import the robot onto the current stage and retrieve its prim path
51 result, prim_path = omni.kit.commands.execute(
52 "URDFImportRobot",
53 urdf_robot=robot_model,
54 import_config=import_config,
55 )
56
57 # Optionally, import the robot onto a new stage and reference it in the current stage
58 # (Useful for assets with textures to ensure textures load correctly)
59 # dest_path = "/path/to/dest.usd"
60 # result, prim_path = omni.kit.commands.execute(
61 # "URDFParseAndImportFile",
62 # urdf_path="{}/{}".format(root_path, file_name),
63 # import_config=import_config,
64 # dest_path=dest_path
65 # )
66 # prim_path = omni.usd.get_stage_next_free_path(
67 # self.world.scene.stage, str(current_stage.GetDefaultPrim().GetPath()) + prim_path, False
68 # )
69 # robot_prim = self.world.scene.stage.OverridePrim(prim_path)
70 # robot_prim.GetReferences().AddReference(dest_path)
71
72 # Initialize a predefined task for the robot (e.g., following a target)
73 my_task = FollowTarget(
74 name="follow_target_task",
75 franka_prim_path=prim_path, # Path to the robot's prim in the scene
76 franka_robot_name="fancy_franka", # Name for the robot instance
77 target_name="target" # Name of the target object the robot should follow
78 )
79
80 # Add the task to the simulation world
81 world.add_task(my_task)
82 return
83
84 async def setup_post_load(self):
85 # Set up post-load configurations, such as controllers
86 self._world = self.get_world()
87 self._franka = self._world.scene.get_object("fancy_franka")
88
89 # Initialize the RMPFlow controller for the robot
90 self._controller = RMPFlowController(
91 name="target_follower_controller",
92 robot_articulation=self._franka
93 )
94
95 # Add a physics callback for simulation steps
96 self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
97 await self._world.play_async()
98 return
99
100 async def setup_post_reset(self):
101 # Reset the controller to its initial state
102 self._controller.reset()
103 await self._world.play_async()
104 return
105
106 def physics_step(self, step_size):
107 # Perform a simulation step and compute actions for the robot
108 world = self.get_world()
109 observations = world.get_observations()
110
111 # Compute actions for the robot to follow the target's position and orientation
112 actions = self._controller.forward(
113 target_end_effector_position=observations["target"]["position"],
114 target_end_effector_orientation=observations["target"]["orientation"]
115 )
116
117 # Apply the computed actions to the robot
118 self._franka.apply_action(actions)
119 return
Press
Ctrl+S
to save the code and hot-reload NVIDIA Isaac Sim.Click the File > New From Stage Template > Empty to create a new stage. Click Don’t Save if the simulator is prompting you to save the stage.
Open the menu again and load the example.
Click the LOAD button and move the target prim around to see the robot follow it.
Importing a URDF through a ROS2 node is a powerful way to integrate NVIDIA Isaac Sim with your existing ROS2 workflow. This allows you to import a URDF from a ROS2 node and use it in NVIDIA Isaac Sim, also indirectly enabling importing XACRO definitions without explicit conversion to URDF.
Note
This tutorial is only supported on Linux.
Prerequisites
A ROS 2 workspace with a robot description (e.g. Universal Robots ROS2 Description ).
Follow the tutorials on how to set up a ROS2 workspace (Humble) and include a robot description like the one in this example, along with all its dependencies.
Steps
- Terminal 1
Source ROS 2
Launch a transform publisher for the robot description node (e.g.
ros2 launch ur_description view_ur.launch.py ur_type:=ur10e
)
- Terminal 2
Source ROS 2
Pick the ROS 2 node name for the node just created with
ros2 node list
. (for example,robot_state_publisher
)
- Terminal 3
Source ROS 2
Start Isaac Sim
Enable the extension
isaacsim.ros2.urdf
Open the URDF Importer using the File > Import from ROS2 URDF Node menu
Put the node name in the text box
Define an output directory
Import
Extra steps to try:
- Terminal 1
Stop the publisher, change it to another robot and start service again (for example,
ros2 launch ur_description view_ur.launch.py ur_type:=ur3
)
- Terminal 3
Click the Refresh button
Change the output directory
Import
The robot is now imported into the stage. You can now use it in your simulation. You can perform additional changes to the asset once it’s imported, such as adding sensors, changing materials, and updating the joint drives and configuration to achieve a more stable simulation. Robots are mapped as Articulations in the simulation, and for a complete guide in tuning articulations, refer to Articulation Stability Guide
Summary#
This tutorial covered the following topics:
Importing URDF file using GUI
Importing URDF file using Python
Importing URDF file using a ROS Node
Using the imported URDF in a Task
Visualizing collision meshes
Setting up importing a robot with the UI through the built-in examples
Further Learning#
Checkout URDF Importer Extension to learn more about the different configuration settings to import a URDF in NVIDIA Isaac Sim.