Import URDF
Learning Objectives
This tutorial shows how to import a urdf and convert it to a usd in Omniverse Isaac Sim. After this tutorial, you can use urdf files in your pipeline while using Omniverse Isaac Sim.
5-10 Minute Tutorial
Getting Started
Prerequisites
Review the Introductory Tutorial Series prior to beginning this tutorial.
Using the URDF Importer Extension Window
Let’s begin by importing a Franka Panda URDF from the Built in URDF files that come with the extension.
Enable the omni.importer.urdf extension in Omniverse Isaac Sim if it is not automatically loaded by going to Window-> Extensions and enable omni.importer.urdf.
Accessed the urdf externsion by going to the Isaac Utils -> Workflows -> URDF Importer menu.
Let’s specify the settings we want to import Franka with:
Check the box next to Fix Base Link, and Create Physics Scene only.
Set Stage Units Per Meters to 1.0, which means the asset will be imported in meters
Set the joint drive type to Position
Set Joint Drive Strength and Joint Position Drive Damping to 10000000.0 and 100000.0
Set the Output Directory to the place where you store your assets (nucleus or Local)
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.
In the file Input File box under the Import tab, 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/robots/franka_description/robots folder that comes with this extension.
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:
If you are importing a mobile robot, you may need to change the following settings
Uncheck Fix Base Link
Set the joint drive type to Velocity drive
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 0 in velocity drive mode.
Importing URDF using Python
Let’s do the exact same things as we did before but with python scripting instead. We will then use the imported robot with one of the tasks defined under omni.isaac.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 Isaac Examples > 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 omni.isaac.examples.base_sample import BaseSample 2from omni.isaac.core.utils.extensions import get_extension_path_from_name 3from omni.importer.urdf import _urdf 4from omni.isaac.franka.controllers import RMPFlowController 5from omni.isaac.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 world = self.get_world() 16 world.scene.add_default_ground_plane() 17 # Acquire the URDF extension interface 18 urdf_interface = _urdf.acquire_urdf_interface() 19 # Set the settings in the import config 20 import_config = _urdf.ImportConfig() 21 import_config.merge_fixed_joints = False 22 import_config.convex_decomp = False 23 import_config.fix_base = True 24 import_config.make_default_prim = True 25 import_config.self_collision = False 26 import_config.create_physics_scene = True 27 import_config.import_inertia_tensor = False 28 import_config.default_drive_strength = 1047.19751 29 import_config.default_position_drive_damping = 52.35988 30 import_config.default_drive_type = _urdf.UrdfJointTargetType.JOINT_DRIVE_POSITION 31 import_config.distance_scale = 1 32 import_config.density = 0.0 33 # Get the urdf file path 34 extension_path = get_extension_path_from_name("omni.importer.urdf") 35 root_path = extension_path + "/data/urdf/robots/franka_description/robots" 36 file_name = "panda_arm_hand.urdf" 37 # Finally import the robot 38 result, prim_path = omni.kit.commands.execute( "URDFParseAndImportFile", urdf_path="{}/{}".format(root_path, file_name), 39 import_config=import_config,) 40 # Optionally, you could also provide a `dest_path` parameter stage path to URDFParseAndImportFile, 41 # which would import the robot on a new stage, in which case you'd need to add it to current stage as a reference: 42 # dest_path = "/path/to/dest.usd 43 # result, prim_path = omni.kit.commands.execute( "URDFParseAndImportFile", urdf_path="{}/{}".format(root_path, file_name), 44 # import_config=import_config,dest_path = dest_path) 45 # prim_path = omni.usd.get_stage_next_free_path( 46 # self.world.scene.stage, str(current_stage.GetDefaultPrim().GetPath()) + prim_path, False 47 # ) 48 # robot_prim = self.world.scene.stage.OverridePrim(prim_path) 49 # robot_prim.GetReferences().AddReference(dest_path) 50 # This is required for robot assets that contain texture, otherwise texture won't be loaded. 51 52 # Now lets use it with one of the tasks defined under omni.isaac.franka 53 # Similar to what was covered in Tutorial 6 Adding a Manipulator in the Required Tutorials 54 my_task = FollowTarget(name="follow_target_task", franka_prim_path=prim_path, 55 franka_robot_name="fancy_franka", target_name="target") 56 world.add_task(my_task) 57 return 58 59 async def setup_post_load(self): 60 self._world = self.get_world() 61 self._franka = self._world.scene.get_object("fancy_franka") 62 self._controller = RMPFlowController(name="target_follower_controller", robot_articulation=self._franka) 63 self._world.add_physics_callback("sim_step", callback_fn=self.physics_step) 64 await self._world.play_async() 65 return 66 67 async def setup_post_reset(self): 68 self._controller.reset() 69 await self._world.play_async() 70 return 71 72 def physics_step(self, step_size): 73 world = self.get_world() 74 observations = world.get_observations() 75 actions = self._controller.forward( 76 target_end_effector_position=observations["target"]["position"], 77 target_end_effector_orientation=observations["target"]["orientation"], 78 ) 79 self._franka.apply_action(actions) 80 return
Press
Ctrl+S
to save the code and hot-reload Omniverse 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
Summary
This tutorial covered the following topics:
Importing URDF file using GUI
Importing URDF file using Python
Using the imported URDF in a Task
Visualizing collision meshes
Further Learning
Checkout URDF Importer to learn more about the different configuration settings to import a urdf in Omniverse Isaac Sim.