isaaclab.sim.converters

Contents

isaaclab.sim.converters#

Sub-module containing converters for converting various file types to USD.

In order to support direct loading of various file types into Omniverse, we provide a set of converters that can convert the file into a USD file. The converters are implemented as sub-classes of the AssetConverterBase class.

The following converters are currently supported:

  • UrdfConverter: Converts a URDF file into a USD file.

  • MeshConverter: Converts a mesh file into a USD file. This supports OBJ, STL and FBX files.

Classes

AssetConverterBase

Base class for converting an asset file from different formats into USD format.

AssetConverterBaseCfg

The base configuration class for asset converters.

MeshConverter

Converter for a mesh file in OBJ / STL / FBX format to a USD file.

MeshConverterCfg

The configuration class for MeshConverter.

UrdfConverter

Converter for a URDF description file to a USD file.

UrdfConverterCfg

The configuration class for UrdfConverter.

Asset Converter Base#

class isaaclab.sim.converters.AssetConverterBase[source]#

Base class for converting an asset file from different formats into USD format.

This class provides a common interface for converting an asset file into USD. It does not provide any implementation for the conversion. The derived classes must implement the _convert_asset() method to provide the actual conversion.

The file conversion is lazy if the output directory (AssetConverterBaseCfg.usd_dir) is provided. In the lazy conversion, the USD file is re-generated only if:

  • The asset file is modified.

  • The configuration parameters are modified.

  • The USD file does not exist.

To override this behavior to force conversion, the flag AssetConverterBaseCfg.force_usd_conversion can be set to True.

When no output directory is defined, lazy conversion is deactivated and the generated USD file is stored in folder /tmp/IsaacLab/usd_{date}_{time}_{random}, where the parameters in braces are generated at runtime. The random identifiers help avoid a race condition where two simultaneously triggered conversions try to use the same directory for reading/writing the generated files.

Note

Changes to the parameters AssetConverterBaseCfg.asset_path, AssetConverterBaseCfg.usd_dir, and AssetConverterBaseCfg.usd_file_name are not considered as modifications in the configuration instance that trigger USD file re-generation.

Methods:

__init__(cfg)

Initializes the class.

Attributes:

usd_dir

The absolute path to the directory where the generated USD files are stored.

usd_file_name

The file name of the generated USD file.

usd_path

The absolute path to the generated USD file.

usd_instanceable_meshes_path

The relative path to the USD file with meshes.

__init__(cfg: AssetConverterBaseCfg)[source]#

Initializes the class.

Parameters:

cfg – The configuration instance for converting an asset file to USD format.

Raises:

ValueError – When provided asset file does not exist.

property usd_dir: str#

The absolute path to the directory where the generated USD files are stored.

property usd_file_name: str#

The file name of the generated USD file.

property usd_path: str#

The absolute path to the generated USD file.

property usd_instanceable_meshes_path: str#

The relative path to the USD file with meshes.

The path is with respect to the USD directory usd_dir. This is to ensure that the mesh references in the generated USD file are resolved relatively. Otherwise, it becomes difficult to move the USD asset to a different location.

class isaaclab.sim.converters.AssetConverterBaseCfg[source]#

The base configuration class for asset converters.

Attributes:

asset_path

The absolute path to the asset file to convert into USD.

usd_dir

The output directory path to store the generated USD file.

usd_file_name

The name of the generated usd file.

force_usd_conversion

Force the conversion of the asset file to usd.

make_instanceable

Make the generated USD file instanceable.

asset_path: str#

The absolute path to the asset file to convert into USD.

usd_dir: str | None#

The output directory path to store the generated USD file. Defaults to None.

If None, it is resolved as /tmp/IsaacLab/usd_{date}_{time}_{random}, where the parameters in braces are runtime generated.

usd_file_name: str | None#

The name of the generated usd file. Defaults to None.

If None, it is resolved from the asset file name. For example, if the asset file name is "my_asset.urdf", then the generated USD file name is "my_asset.usd".

If the providing file name does not end with “.usd” or “.usda”, then the extension “.usd” is appended to the file name.

force_usd_conversion: bool#

Force the conversion of the asset file to usd. Defaults to False.

If True, then the USD file is always generated. It will overwrite the existing USD file if it exists.

make_instanceable: bool#

Make the generated USD file instanceable. Defaults to True.

Note

Instancing helps reduce the memory footprint of the asset when multiple copies of the asset are used in the scene. For more information, please check the USD documentation on scene-graph instancing.

Mesh Converter#

class isaaclab.sim.converters.MeshConverter[source]#

Bases: AssetConverterBase

Converter for a mesh file in OBJ / STL / FBX format to a USD file.

This class wraps around the omni.kit.asset_converter extension to provide a lazy implementation for mesh to USD conversion. It stores the output USD file in an instanceable format since that is what is typically used in all learning related applications.

To make the asset instanceable, we must follow a certain structure dictated by how USD scene-graph instancing and physics work. The rigid body component must be added to each instance and not the referenced asset (i.e. the prototype prim itself). This is because the rigid body component defines properties that are specific to each instance and cannot be shared under the referenced asset. For more information, please check the documentation.

Due to the above, we follow the following structure:

  • {prim_path} - The root prim that is an Xform with the rigid body and mass APIs if configured.

  • {prim_path}/geometry - The prim that contains the mesh and optionally the materials if configured. If instancing is enabled, this prim will be an instanceable reference to the prototype prim.

Caution

When converting STL files, Z-up convention is assumed, even though this is not the default for many CAD export programs. Asset orientation convention can either be modified directly in the CAD program’s export process or an offset can be added within the config in Isaac Lab.

Attributes:

cfg

The configuration instance for mesh to USD conversion.

usd_dir

The absolute path to the directory where the generated USD files are stored.

usd_file_name

The file name of the generated USD file.

usd_instanceable_meshes_path

The relative path to the USD file with meshes.

usd_path

The absolute path to the generated USD file.

Methods:

__init__(cfg)

Initializes the class.

cfg: MeshConverterCfg#

The configuration instance for mesh to USD conversion.

__init__(cfg: MeshConverterCfg)[source]#

Initializes the class.

Parameters:

cfg – The configuration instance for mesh to USD conversion.

property usd_dir: str#

The absolute path to the directory where the generated USD files are stored.

property usd_file_name: str#

The file name of the generated USD file.

property usd_instanceable_meshes_path: str#

The relative path to the USD file with meshes.

The path is with respect to the USD directory usd_dir. This is to ensure that the mesh references in the generated USD file are resolved relatively. Otherwise, it becomes difficult to move the USD asset to a different location.

property usd_path: str#

The absolute path to the generated USD file.

class isaaclab.sim.converters.MeshConverterCfg[source]#

Bases: AssetConverterBaseCfg

The configuration class for MeshConverter.

Attributes:

mass_props

Mass properties to apply to the USD.

rigid_props

Rigid body properties to apply to the USD.

collision_props

Collision properties to apply to the USD.

asset_path

The absolute path to the asset file to convert into USD.

usd_dir

The output directory path to store the generated USD file.

usd_file_name

The name of the generated usd file.

force_usd_conversion

Force the conversion of the asset file to usd.

make_instanceable

Make the generated USD file instanceable.

collision_approximation

Collision approximation method to use.

translation

The translation of the mesh to the origin.

rotation

The rotation of the mesh in quaternion format (w, x, y, z).

scale

The scale of the mesh.

mass_props: MassPropertiesCfg | None#

Mass properties to apply to the USD. Defaults to None.

Note

If None, then no mass properties will be added.

rigid_props: RigidBodyPropertiesCfg | None#

Rigid body properties to apply to the USD. Defaults to None.

Note

If None, then no rigid body properties will be added.

collision_props: CollisionPropertiesCfg | None#

Collision properties to apply to the USD. Defaults to None.

Note

If None, then no collision properties will be added.

asset_path: str#

The absolute path to the asset file to convert into USD.

usd_dir: str | None#

The output directory path to store the generated USD file. Defaults to None.

If None, it is resolved as /tmp/IsaacLab/usd_{date}_{time}_{random}, where the parameters in braces are runtime generated.

usd_file_name: str | None#

The name of the generated usd file. Defaults to None.

If None, it is resolved from the asset file name. For example, if the asset file name is "my_asset.urdf", then the generated USD file name is "my_asset.usd".

If the providing file name does not end with “.usd” or “.usda”, then the extension “.usd” is appended to the file name.

force_usd_conversion: bool#

Force the conversion of the asset file to usd. Defaults to False.

If True, then the USD file is always generated. It will overwrite the existing USD file if it exists.

make_instanceable: bool#

Make the generated USD file instanceable. Defaults to True.

Note

Instancing helps reduce the memory footprint of the asset when multiple copies of the asset are used in the scene. For more information, please check the USD documentation on scene-graph instancing.

collision_approximation: str#

Collision approximation method to use. Defaults to “convexDecomposition”.

Valid options are: “convexDecomposition”, “convexHull”, “boundingCube”, “boundingSphere”, “meshSimplification”, or “none”

“none” causes no collision mesh to be added.

translation: tuple[float, float, float]#

The translation of the mesh to the origin. Defaults to (0.0, 0.0, 0.0).

rotation: tuple[float, float, float, float]#

The rotation of the mesh in quaternion format (w, x, y, z). Defaults to (1.0, 0.0, 0.0, 0.0).

scale: tuple[float, float, float]#

The scale of the mesh. Defaults to (1.0, 1.0, 1.0).

URDF Converter#

class isaaclab.sim.converters.UrdfConverter[source]#

Bases: AssetConverterBase

Converter for a URDF description file to a USD file.

This class wraps around the isaacsim.asset.importer.urdf extension to provide a lazy implementation for URDF to USD conversion. It stores the output USD file in an instanceable format since that is what is typically used in all learning related applications.

Caution

The current lazy conversion implementation does not automatically trigger USD generation if only the mesh files used by the URDF are modified. To force generation, either set AssetConverterBaseCfg.force_usd_conversion to True or delete the output directory.

Note

From Isaac Sim 4.5 onwards, the extension name changed from omni.importer.urdf to isaacsim.asset.importer.urdf. This converter class now uses the latest extension from Isaac Sim.

Attributes:

cfg

The configuration instance for URDF to USD conversion.

usd_dir

The absolute path to the directory where the generated USD files are stored.

usd_file_name

The file name of the generated USD file.

usd_instanceable_meshes_path

The relative path to the USD file with meshes.

usd_path

The absolute path to the generated USD file.

Methods:

__init__(cfg)

Initializes the class.

cfg: UrdfConverterCfg#

The configuration instance for URDF to USD conversion.

__init__(cfg: UrdfConverterCfg)[source]#

Initializes the class.

Parameters:

cfg – The configuration instance for URDF to USD conversion.

property usd_dir: str#

The absolute path to the directory where the generated USD files are stored.

property usd_file_name: str#

The file name of the generated USD file.

property usd_instanceable_meshes_path: str#

The relative path to the USD file with meshes.

The path is with respect to the USD directory usd_dir. This is to ensure that the mesh references in the generated USD file are resolved relatively. Otherwise, it becomes difficult to move the USD asset to a different location.

property usd_path: str#

The absolute path to the generated USD file.

class isaaclab.sim.converters.UrdfConverterCfg[source]#

Bases: AssetConverterBaseCfg

The configuration class for UrdfConverter.

Classes:

JointDriveCfg

JointDriveCfg(drive_type: Union[dict[str, Literal['acceleration', 'force']], Literal['acceleration', 'force']] = <factory>, target_type: Union[dict[str, Literal['none', 'position', 'velocity']], Literal['none', 'position', 'velocity']] = <factory>, gains: isaaclab.sim.converters.urdf_converter_cfg.UrdfConverterCfg.JointDriveCfg.PDGainsCfg | isaaclab.sim.converters.urdf_converter_cfg.UrdfConverterCfg.JointDriveCfg.NaturalFrequencyGainsCfg = <factory>)

Attributes:

fix_base

Create a fix joint to the root/base link.

asset_path

The absolute path to the asset file to convert into USD.

usd_dir

The output directory path to store the generated USD file.

usd_file_name

The name of the generated usd file.

force_usd_conversion

Force the conversion of the asset file to usd.

make_instanceable

Make the generated USD file instanceable.

root_link_name

The name of the root link.

link_density

Default density in kg/m^3 for links whose "inertial" properties are missing in the URDF.

merge_fixed_joints

Consolidate links that are connected by fixed joints.

convert_mimic_joints_to_normal_joints

Convert mimic joints to normal joints.

joint_drive

The joint drive settings.

collision_from_visuals

Create collision geometry from visual geometry.

collider_type

The collision shape simplification.

self_collision

Activate self-collisions between links of the articulation.

replace_cylinders_with_capsules

Replace cylinder shapes with capsule shapes.

class JointDriveCfg[source]#

Bases: object

JointDriveCfg(drive_type: Union[dict[str, Literal[‘acceleration’, ‘force’]], Literal[‘acceleration’, ‘force’]] = <factory>, target_type: Union[dict[str, Literal[‘none’, ‘position’, ‘velocity’]], Literal[‘none’, ‘position’, ‘velocity’]] = <factory>, gains: isaaclab.sim.converters.urdf_converter_cfg.UrdfConverterCfg.JointDriveCfg.PDGainsCfg | isaaclab.sim.converters.urdf_converter_cfg.UrdfConverterCfg.JointDriveCfg.NaturalFrequencyGainsCfg = <factory>)

Classes:

PDGainsCfg

Configuration for the PD gains of the drive.

NaturalFrequencyGainsCfg

Configuration for the natural frequency gains of the drive.

Attributes:

drive_type

The drive type used for the joint.

target_type

The drive target type used for the joint.

gains

The drive gains configuration.

class PDGainsCfg[source]#

Bases: object

Configuration for the PD gains of the drive.

Attributes:

stiffness

The stiffness of the joint drive in Nm/rad or N/rad.

damping

The damping of the joint drive in Nm/(rad/s) or N/(rad/s).

stiffness: dict[str, float] | float#

The stiffness of the joint drive in Nm/rad or N/rad.

If None, the stiffness is set to the value parsed from the URDF file. If target_type is set to "velocity", this value determines the drive strength in joint velocity space.

damping: dict[str, float] | float | None#

The damping of the joint drive in Nm/(rad/s) or N/(rad/s). Defaults to None.

If None, the damping is set to the value parsed from the URDF file or 0.0 if no value is found in the URDF. If target_type is set to "velocity", this attribute is set to 0.0 and stiffness serves as the drive’s strength in joint velocity space.

class NaturalFrequencyGainsCfg[source]#

Bases: object

Configuration for the natural frequency gains of the drive.

Computes the joint drive stiffness and damping based on the desired natural frequency using the formula:

\(P = m \cdot f^2\), \(D = 2 \cdot r \cdot f \cdot m\)

where \(f\) is the natural frequency, \(r\) is the damping ratio, and \(m\) is the total equivalent inertia at the joint. The damping ratio is such that:

  • \(r = 1.0\) is a critically damped system,

  • \(r < 1.0\) is underdamped,

  • \(r > 1.0\) is overdamped.

Attributes:

natural_frequency

The natural frequency of the joint drive.

damping_ratio

The damping ratio of the joint drive.

natural_frequency: dict[str, float] | float#

The natural frequency of the joint drive.

If target_type is set to "velocity", this value determines the drive’s natural frequency in joint velocity space.

damping_ratio: dict[str, float] | float#

The damping ratio of the joint drive. Defaults to 0.005.

If target_type is set to "velocity", this value is ignored and only natural_frequency is used.

drive_type: dict[str, Literal['acceleration', 'force']] | Literal['acceleration', 'force']#

The drive type used for the joint. Defaults to "force".

  • "acceleration": The joint drive normalizes the inertia before applying the joint effort so it’s invariant to inertia and mass changes (equivalent to ideal damped oscillator).

  • "force": Applies effort through forces, so is subject to variations on the body inertia.

target_type: dict[str, Literal['none', 'position', 'velocity']] | Literal['none', 'position', 'velocity']#

The drive target type used for the joint. Defaults to "position".

If the target type is set to "none", the joint stiffness and damping are set to 0.0.

gains: PDGainsCfg | NaturalFrequencyGainsCfg#

The drive gains configuration.

fix_base: bool#

Create a fix joint to the root/base link.

asset_path: str#

The absolute path to the asset file to convert into USD.

usd_dir: str | None#

The output directory path to store the generated USD file. Defaults to None.

If None, it is resolved as /tmp/IsaacLab/usd_{date}_{time}_{random}, where the parameters in braces are runtime generated.

usd_file_name: str | None#

The name of the generated usd file. Defaults to None.

If None, it is resolved from the asset file name. For example, if the asset file name is "my_asset.urdf", then the generated USD file name is "my_asset.usd".

If the providing file name does not end with “.usd” or “.usda”, then the extension “.usd” is appended to the file name.

force_usd_conversion: bool#

Force the conversion of the asset file to usd. Defaults to False.

If True, then the USD file is always generated. It will overwrite the existing USD file if it exists.

make_instanceable: bool#

Make the generated USD file instanceable. Defaults to True.

Note

Instancing helps reduce the memory footprint of the asset when multiple copies of the asset are used in the scene. For more information, please check the USD documentation on scene-graph instancing.

The name of the root link. Defaults to None.

If None, the root link will be set by PhysX.

Default density in kg/m^3 for links whose "inertial" properties are missing in the URDF. Defaults to 0.0.

merge_fixed_joints: bool#

Consolidate links that are connected by fixed joints. Defaults to True.

convert_mimic_joints_to_normal_joints: bool#

Convert mimic joints to normal joints. Defaults to False.

joint_drive: JointDriveCfg | None#

The joint drive settings.

None can be used for URDFs without joints.

collision_from_visuals: bool#

Create collision geometry from visual geometry.

collider_type: Literal['convex_hull', 'convex_decomposition']#

The collision shape simplification. Defaults to "convex_hull".

  • "convex_hull": The collision shape is simplified to a convex hull.

  • "convex_decomposition": The collision shape is decomposed into smaller convex shapes for a closer fit.

self_collision: bool#

Activate self-collisions between links of the articulation. Defaults to False.

replace_cylinders_with_capsules: bool#

Replace cylinder shapes with capsule shapes. Defaults to False.