URDF Import Extension [omni.importer.urdf]
URDF Import Commands
The following commands can be used to simplify the import process. Below is a sample demonstrating how to import the Carter URDF included with this extension
1import omni.kit.commands
2from pxr import UsdLux, Sdf, Gf, UsdPhysics, PhysicsSchemaTools
3
4# setting up import configuration:
5status, import_config = omni.kit.commands.execute("URDFCreateImportConfig")
6import_config.merge_fixed_joints = False
7import_config.convex_decomp = False
8import_config.import_inertia_tensor = True
9import_config.fix_base = False
10import_config.collision_from_visuals = False
11
12# Get path to extension data:
13ext_manager = omni.kit.app.get_app().get_extension_manager()
14ext_id = ext_manager.get_enabled_extension_id("omni.importer.urdf")
15extension_path = ext_manager.get_extension_path(ext_id)
16# import URDF
17omni.kit.commands.execute(
18 "URDFParseAndImportFile",
19 urdf_path=extension_path + "/data/urdf/robots/carter/urdf/carter.urdf",
20 import_config=import_config,
21)
22# get stage handle
23stage = omni.usd.get_context().get_stage()
24
25# enable physics
26scene = UsdPhysics.Scene.Define(stage, Sdf.Path("/physicsScene"))
27# set gravity
28scene.CreateGravityDirectionAttr().Set(Gf.Vec3f(0.0, 0.0, -1.0))
29scene.CreateGravityMagnitudeAttr().Set(9.81)
30
31# add ground plane
32PhysicsSchemaTools.addGroundPlane(stage, "/World/groundPlane", "Z", 1500, Gf.Vec3f(0, 0, -50), Gf.Vec3f(0.5))
33
34# add lighting
35distantLight = UsdLux.DistantLight.Define(stage, Sdf.Path("/DistantLight"))
36distantLight.CreateIntensityAttr(500)
- class omni.importer.urdf.scripts.commands.URDFCreateImportConfig(*args: Any, **kwargs: Any)
Returns an ImportConfig object that can be used while parsing and importing. Should be used with URDFParseFile and URDFParseAndImportFile commands
- Returns
Parsed URDF stored in an internal structure.
- Return type
- class omni.importer.urdf.scripts.commands.URDFParseText(*args: Any, **kwargs: Any)
This command parses a given urdf and returns a UrdfRobot object
- Parameters
arg0 (
str
) – The absolute path to where the urdf file isarg1 (
omni.importer.urdf._urdf.ImportConfig
) – Import Configuration
- Returns
Parsed URDF stored in an internal structure.
- Return type
omni.importer.urdf._urdf.UrdfRobot
- class omni.importer.urdf.scripts.commands.URDFParseFile(*args: Any, **kwargs: Any)
This command parses a given urdf and returns a UrdfRobot object
- Parameters
arg0 (
str
) – The absolute path to where the urdf file isarg1 (
omni.importer.urdf._urdf.ImportConfig
) – Import Configuration
- Returns
Parsed URDF stored in an internal structure.
- Return type
omni.importer.urdf._urdf.UrdfRobot
- class omni.importer.urdf.scripts.commands.URDFImportRobot(*args: Any, **kwargs: Any)
This command parses and imports a given urdf and returns a UrdfRobot object
- Parameters
arg0 (
str
) – The absolute path to where the urdf file isarg1 (
UrdfRobot
) – The parsed URDF Robotarg2 (
omni.importer.urdf._urdf.ImportConfig
) – Import Configurationarg3 (
str
) – destination path for robot usd. Default is “” which will load the robot in-memory on the open stage.arg4 (
bool
) – if True, return the articulation Root prim path instead of the object’s base path.
- Returns
Path to the robot on the USD stage.
- Return type
str
- class omni.importer.urdf.scripts.commands.URDFParseAndImportFile(*args: Any, **kwargs: Any)
This command parses and imports a given urdf and returns a UrdfRobot object
- Parameters
arg0 (
str
) – The absolute path to where the urdf file isarg1 (
omni.importer.urdf._urdf.ImportConfig
) – Import Configurationarg2 (
str
) – destination path for robot usd. Default is “” which will load the robot in-memory on the open stage.arg3 (
bool
) – if True, return the articulation Root prim path instead of the object’s base path.
- Returns
Path to the robot on the USD stage.
- Return type
str
This extension provides an interface to the URDF importer.
Example
Setup the configuration parameters before importing. Files must be parsed before imported.
from omni.importer.urdf import _urdf
urdf_interface = _urdf.acquire_urdf_interface()
# setup config params
import_config = _urdf.ImportConfig()
import_config.set_merge_fixed_joints(False)
import_config.set_fix_base(True)
# parse and import file
imported_robot = urdf_interface.parse_urdf(robot_path, filename, import_config)
urdf_interface.import_robot(robot_path, filename, imported_robot, import_config, "")
Refer to the sample documentation for more examples and usage
- class omni.importer.urdf._urdf.Urdf
- get_kinematic_chain(self: omni.importer.urdf._urdf.Urdf, arg0: omni.importer.urdf._urdf.UrdfRobot) dict
Get the kinematic chain of the robot. Mostly used for graphic display of the kinematic tree.
- Parameters
arg0 (
omni.importer.urdf._urdf.UrdfRobot
) – The parsed URDF, the output fromparse_urdf
- Returns
A dictionary with information regarding the parent-child relationship between all the links and joints
- Return type
dict
- import_robot(self: omni.importer.urdf._urdf.Urdf, assetRoot: str, assetName: str, robot: omni.importer.urdf._urdf.UrdfRobot, importConfig: omni.importer.urdf._urdf.ImportConfig, stage: str = '', getArticulationRoot: bool = False) str
Importing the robot, from the already parsed URDF file.
- Parameters
arg0 (
str
) – The absolute path to where the urdf file isarg1 (
str
) – The name of the urdf filearg2 (
omni.importer.urdf._urdf.UrdfRobot
) – The parsed URDF file, the output fromparse_urdf
arg3 (
omni.importer.urdf._urdf.ImportConfig
) – Import configuration parametersarg4 (
str
) – optional: path to stage to use for importing. leaving it empty will import on open stage. If the open stage is a new stage, textures will not load.
- Returns
Path to the robot on the USD stage.
- Return type
str
- parse_string_urdf(self: omni.importer.urdf._urdf.Urdf, arg0: str, arg1: omni.importer.urdf._urdf.ImportConfig) omni.importer.urdf._urdf.UrdfRobot
Parse URDF file into the internal data structure, which is displayed in the importer window for inspection.
- Parameters
arg0 (
str
) – The urdf in text formatarg2 (
omni.importer.urdf._urdf.ImportConfig
) – Import configuration parameters
- Returns
Parsed URDF stored in an internal structure.
- Return type
omni.importer.urdf._urdf.UrdfRobot
- parse_urdf(self: omni.importer.urdf._urdf.Urdf, arg0: str, arg1: str, arg2: omni.importer.urdf._urdf.ImportConfig) omni.importer.urdf._urdf.UrdfRobot
Parse URDF file into the internal data structure, which is displayed in the importer window for inspection.
- Parameters
arg0 (
str
) – The absolute path to where the urdf file isarg1 (
str
) – The name of the urdf filearg2 (
omni.importer.urdf._urdf.ImportConfig
) – Import configuration parameters
- Returns
Parsed URDF stored in an internal structure.
- Return type
omni.importer.urdf._urdf.UrdfRobot
- class omni.importer.urdf._urdf.ImportConfig
- property collision_from_visuals
Generate convex collision from the visual meshes.
- property convex_decomp
Decompose a convex mesh into smaller pieces for a closer fit
- property create_physics_scene
add a physics scene to the stage on import if none exists
- property default_drive_strength
default drive stiffness used for joints if drive type is position or velocity and none is authored
- property default_drive_type
default drive type used for joints
- property default_position_drive_damping
default drive damping used if drive type is set to position and no damping is authored
- property density
default density used for links, use 0 to autocompute
- property distance_scale
Set the unit scaling factor, 1.0 means meters, 100.0 means cm
- property fix_base
Create fix joint for base link
- property import_inertia_tensor
Import inertia tensor from urdf, if not specified in urdf it will import as identity
- property instanceable_usd_path
USD file to store instanceable mehses in
- property make_default_prim
set imported robot as default prim
- property make_instanceable
Creates an instanceable version of the asset. All meshes will be placed in a separate USD file
- property merge_fixed_joints
Consolidating links that are connected by fixed joints
- property override_joint_dynamics
Use default values for all joints
- property parse_mimic
Parse Mimic Joint flag using PhysX Tendons
- property replace_cylinders_with_capsules
Replace all cylinder bodies in the URDF with capsules.
- property self_collision
Self collisions between links in the articulation
- set_collision_from_visuals(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_convex_decomp(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_create_physics_scene(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_default_drive_strength(self: omni.importer.urdf._urdf.ImportConfig, arg0: float) None
- set_default_drive_type(self: omni.importer.urdf._urdf.ImportConfig, arg0: int) None
- set_default_position_drive_damping(self: omni.importer.urdf._urdf.ImportConfig, arg0: float) None
- set_density(self: omni.importer.urdf._urdf.ImportConfig, arg0: float) None
- set_distance_scale(self: omni.importer.urdf._urdf.ImportConfig, arg0: float) None
- set_fix_base(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_import_inertia_tensor(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_instanceable_usd_path(self: omni.importer.urdf._urdf.ImportConfig, arg0: str) None
- set_make_default_prim(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_make_instanceable(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_merge_fixed_joints(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_override_joint_dynamics(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_parse_mimic(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_replace_cylinders_with_capsules(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_self_collision(self: omni.importer.urdf._urdf.ImportConfig, arg0: bool) None
- set_subdivision_scheme(self: omni.importer.urdf._urdf.ImportConfig, arg0: int) None
- set_up_vector(self: omni.importer.urdf._urdf.ImportConfig, arg0: float, arg1: float, arg2: float) None
- property subdivision_scheme
Subdivision scheme to be used for mesh normals
- property up_vector
Up vector used for import