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
Base class for converting an asset file from different formats into USD format. |
|
The base configuration class for asset converters. |
|
Converter for a mesh file in OBJ / STL / FBX format to a USD file. |
|
The configuration class for MeshConverter. |
|
Converter for a URDF description file to a USD file. |
|
The configuration class for UrdfConverter. |
|
Converter for a MJCF description file to a USD file. |
|
The configuration class for MjcfConverter. |
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_conversioncan 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, andAssetConverterBaseCfg.usd_file_nameare not considered as modifications in the configuration instance that trigger the USD file re-generation.Methods:
__init__(cfg)Initializes the class.
Attributes:
The absolute path to the directory where the generated USD files are stored.
The file name of the generated USD file.
The absolute path to the generated USD file.
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_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:
The absolute path to the asset file to convert into USD.
The output directory path to store the generated USD file.
The name of the generated usd file.
Force the conversion of the asset file to usd.
Make the generated USD file instanceable.
- 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:
AssetConverterBaseConverter 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:
The configuration instance for mesh to USD conversion.
The absolute path to the directory where the generated USD files are stored.
The file name of the generated USD file.
The relative path to the USD file with meshes.
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_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.MeshConverterCfg[source]#
Bases:
AssetConverterBaseCfgThe configuration class for MeshConverter.
Attributes:
Mass properties to apply to the USD.
Rigid body properties to apply to the USD.
Collision properties to apply to the USD.
The absolute path to the asset file to convert into USD.
The output directory path to store the generated USD file.
The name of the generated usd file.
Force the conversion of the asset file to usd.
Make the generated USD file instanceable.
Mesh approximation properties to apply to all collision meshes in the USD.
The translation of the mesh to the origin.
The rotation of the mesh in quaternion format (x, y, z, w).
The scale of the mesh.
- mass_props: MassPropertiesCfg#
Mass properties to apply to the USD. Defaults to None.
Note
If None, then no mass properties will be added.
- rigid_props: RigidBodyBaseCfg#
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#
Collision properties to apply to the USD. Defaults to None.
Note
If None, then no collision properties will be added.
- 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_collision_props: MeshCollisionBaseCfg#
Mesh approximation properties to apply to all collision meshes in the USD. .. note:: If None, then no mesh approximation properties will be added.
- translation: tuple[float, float, float]#
The translation of the mesh to the origin. Defaults to (0.0, 0.0, 0.0).
URDF Converter#
- class isaaclab.sim.converters.UrdfConverter[source]#
Bases:
AssetConverterBaseConverter 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.
The heavy lifting (URDF parsing, fixed-joint merging, fix-base insertion, joint-drive configuration, density override, asset transformer profile) is delegated to Isaac Sim’s
URDFImportertogether withURDFImporterConfig. IsaacLab only translates its user-friendlyUrdfConverterCfginto the flat importer config.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_conversionto True or delete the output directory.Note
From Isaac Sim 4.5 onwards, the extension name changed from
omni.importer.urdftoisaacsim.asset.importer.urdf.Note
In the URDF importer 3.0, the conversion pipeline uses the
urdf-usd-converterlibrary and theisaacsim.asset.transformer.rulesextension to produce structured USD output. Features such asconvert_mimic_joints_to_normal_jointsandreplace_cylinders_with_capsulesare no longer natively supported by the importer and will emit warnings if enabled.Attributes:
The configuration instance for URDF to USD conversion.
The absolute path to the directory where the generated USD files are stored.
The file name of the generated USD file.
The relative path to the USD file with meshes.
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_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.UrdfConverterCfg[source]#
Bases:
AssetConverterBaseCfgThe configuration class for UrdfConverter.
Maps to
URDFImporterConfigfrom the Isaac Sim URDF importer. IsaacLab exposes a user-friendly nestedJointDriveCfgthat is translated into the importer’s flatjoint_drive_type/joint_target_type/override_joint_stiffness/override_joint_dampingfields at conversion time.Classes:
Configuration for the joint drive.
Attributes:
Create a fix joint to the root/base link.
The name of the root link.
Default density in
kg/m^3for links whose"inertial"properties are missing in the URDF.Consolidate links that are connected by fixed joints.
The absolute path to the asset file to convert into USD.
The output directory path to store the generated USD file.
The name of the generated usd file.
Force the conversion of the asset file to usd.
Make the generated USD file instanceable.
Convert mimic joints to normal joints.
The joint drive settings.
Whether to create collision geometry from visual geometry.
The collision shape simplification.
Activate self-collisions between links of the articulation.
Replace cylinder shapes with capsule shapes.
Merge meshes where possible to optimize the model.
ROS package name/path mappings used to resolve
package://URLs in the URDF.Robot type applied by the USD robot schema.
Run the asset transformation profile to convert the flattened USD into a layered USD asset.
Enable to generate compatible MuJoCo attributes from the URDF joint attributes alongside PhysX.
Enable debug mode in the underlying URDF importer.
- class JointDriveCfg[source]#
Bases:
objectConfiguration for the joint drive.
Classes:
Configuration for the PD gains of the drive.
Configuration for the natural frequency gains of the drive.
Attributes:
The drive type used for the joint.
The drive target type used for the joint.
The drive gains configuration.
- class PDGainsCfg[source]#
Bases:
objectConfiguration for the PD gains of the drive.
Attributes:
The stiffness of the joint drive in Nm/rad or N/rad.
The damping of the joint drive in Nm/(rad/s) or N/(rad/s).
- stiffness: dict[str, float] | float | None#
The stiffness of the joint drive in Nm/rad or N/rad. Defaults to None.
If None, the stiffness values produced by the URDF importer are preserved. If
target_typeis 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_typeis set to"velocity", this attribute is set to 0.0 andstiffnessserves as the drive’s strength in joint velocity space.
- class NaturalFrequencyGainsCfg[source]#
Bases:
objectConfiguration 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.
Deprecated since version This: gains mode is no longer supported by the URDF importer 3.0. The
compute_natural_stiffnessfunction has been removed. If used, aDeprecationWarningis emitted and joint drive gains are left at the values produced by the URDF importer. UsePDGainsCfginstead.Attributes:
The natural frequency of the joint drive.
The damping ratio of the joint drive.
- natural_frequency: dict[str, float] | float#
The natural frequency of the joint drive.
If
target_typeis 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_typeis set to"velocity", this value is ignored and onlynatural_frequencyis 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.
- root_link_name: str | None#
The name of the root link. Defaults to None.
If None, the root link will be set by PhysX.
Deprecated since version This: option is no longer supported by the URDF importer 3.0. A warning is logged if set.
- link_density: float#
Default density in
kg/m^3for links whose"inertial"properties are missing in the URDF. Defaults to 0.0.A value of
0.0leaves density unchanged.
- merge_fixed_joints: bool#
Consolidate links that are connected by fixed joints. Defaults to True.
When enabled, a URDF XML pre-processing step removes all fixed joints and merges each child link’s visual, collision, and inertial elements into the parent link before USD conversion. Downstream joints are re-parented with composed transforms. Chains of consecutive fixed joints are handled automatically. The pre-processing is performed by
isaacsim.asset.importer.urdf.impl.urdf_utils.merge_fixed_joints().
- 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.
- convert_mimic_joints_to_normal_joints: bool#
Convert mimic joints to normal joints. Defaults to False.
Deprecated since version This: option is no longer supported by the URDF importer 3.0. A warning is logged if enabled.
- joint_drive: JointDriveCfg | None#
The joint drive settings. Defaults to
JointDriveCfg.The parameter can be set to
Nonefor URDFs without joints, in which case no joint drive overrides are sent to the importer.
- collision_from_visuals: bool#
Whether to create collision geometry from visual geometry. Defaults to False.
- collision_type: Literal['Convex Hull', 'Convex Decomposition', 'Bounding Sphere', 'Bounding Cube']#
The collision shape simplification. Defaults to
"Convex Hull".Supported values match the
collision_typefield ofURDFImporterConfig:"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."Bounding Sphere": The collision shape is approximated by a bounding sphere."Bounding Cube": The collision shape is approximated by a bounding cube.
- 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.
Deprecated since version This: option is no longer supported by the URDF importer 3.0. A warning is logged if enabled.
- ros_package_paths: list[dict[str, str]]#
ROS package name/path mappings used to resolve
package://URLs in the URDF.Each entry is a dictionary with keys
nameandpath. The list is forwarded directly toURDFImporterConfig.
- robot_type: str#
Robot type applied by the USD robot schema. Defaults to
"Default".Supported types are:
Default,End Effector,Manipulator,Humanoid,Wheeled,Holonomic,Quadruped,Mobile Manipulators,Aerial. Forwarded toURDFImporterConfig.
- run_asset_transformer: bool#
Run the asset transformation profile to convert the flattened USD into a layered USD asset. Defaults to True.
After running this profile, the USD asset will be a layered USD asset with the following structure: - robot_name.usda (interface usd) - payloads/base.usda (base usd with links, meshes, and materials) - payloads/instances.usda (usd with visual and collision geometry) - payloads/geometry.usd (binary usd with meshes) - payloads/materials.usda (materials) - payloads/Physics/physics.usda (neutral physics format) - payloads/Physics/physX.usda (PhysX attributes) - payloads/Physics/mujoco.usda (MuJoCo attributes)
MJCF Converter#
- class isaaclab.sim.converters.MjcfConverter[source]#
Bases:
AssetConverterBaseConverter for a MJCF description file to a USD file.
This class wraps around the isaacsim.asset.importer.mjcf extension to provide a lazy implementation for MJCF to USD conversion. All conversion logic (USD schema application, fix-base, density, actuator gains, self-collision, mesh merging, asset transformer profile) is performed by
MJCFImporter— this class only translatesMjcfConverterCfginto a flatMJCFImporterConfig.Caution
The current lazy conversion implementation does not automatically trigger USD generation if only the mesh files used by the MJCF are modified. To force generation, either set
AssetConverterBaseCfg.force_usd_conversionto True or delete the output directory.Note
From Isaac Sim 5.0 onwards, the MJCF importer uses the
mujoco-usd-converterlibrary and theMJCFImporter/MJCFImporterConfigAPI. The old command-based API (MJCFCreateAsset/MJCFCreateImportConfig) is deprecated.Note
The
make_instanceablesetting from the base class is not supported by the new MJCF importer and will be ignored.Attributes:
The configuration instance for MJCF to USD conversion.
The absolute path to the directory where the generated USD files are stored.
The file name of the generated USD file.
The relative path to the USD file with meshes.
The absolute path to the generated USD file.
Methods:
__init__(cfg)Initializes the class.
- cfg: MjcfConverterCfg#
The configuration instance for MJCF to USD conversion.
- __init__(cfg: MjcfConverterCfg)[source]#
Initializes the class.
- Parameters:
cfg – The configuration instance for MJCF to USD conversion.
- 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.MjcfConverterCfg[source]#
Bases:
AssetConverterBaseCfgThe configuration class for MjcfConverter.
Maps to
MJCFImporterConfigfrom the Isaac Sim MJCF importer. All post-import USD edits (fix-base, density override, actuator gain overrides, self-collision, mesh merging, asset transformer profile) are performed by the Isaac Sim importer — this config just forwards the user’s choices.Note
From Isaac Sim 5.0 onwards, the MJCF importer was rewritten to use the
mujoco-usd-converterlibrary. TheAssetConverterBaseCfg.make_instanceablesetting from the base class is not supported by the new MJCF importer and is ignored.Attributes:
Merge meshes where possible to optimize the model.
Generate collision geometry from visual geometries.
Type of collision geometry to use.
Activate self-collisions between links of the articulation.
Import the physics scene (time step per second, gravity, etc.) from the MJCF file.
Add a fixed joint from the world to the root rigid-body link.
Default density in
kg/m^3for links whose"inertial"properties are missing.The absolute path to the asset file to convert into USD.
The output directory path to store the generated USD file.
The name of the generated usd file.
Force the conversion of the asset file to usd.
Make the generated USD file instanceable.
Robot type applied by the USD robot schema.
MuJoCo actuator gain type override (e.g.
"fixed").MuJoCo actuator bias type override (e.g.
"affine").MuJoCo actuator gain parameter array override.
MuJoCo actuator bias parameter array override.
Run the asset transformation profile to convert the flattened USD into a layered USD asset.
Enable to convert compatible MuJoCo attributes to PhysX attributes, such as actuator gains.
Enable debug mode in the underlying MJCF importer.
- collision_from_visuals: bool#
Generate collision geometry from visual geometries. Defaults to False.
- collision_type: Literal['Convex Hull', 'Convex Decomposition', 'Bounding Sphere', 'Bounding Cube']#
Type of collision geometry to use. Defaults to
"Convex Hull".Supported values match the
collision_typefield ofMJCFImporterConfig.
- self_collision: bool#
Activate self-collisions between links of the articulation. Defaults to False.
- import_physics_scene: bool#
Import the physics scene (time step per second, gravity, etc.) from the MJCF file. Defaults to False.
- fix_base: bool#
Add a fixed joint from the world to the root rigid-body link. Defaults to False.
When enabled,
MJCFImporterinserts aFixedJointbetween the world and the articulation root and relocatesArticulationRootAPIonto the appropriate ancestor prim so PhysX treats the articulation as fixed-base.
- link_density: float#
Default density in
kg/m^3for links whose"inertial"properties are missing. Defaults to 0.0.A value of
0.0leaves density unchanged.
- 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.
- robot_type: str#
Robot type applied by the USD robot schema. Defaults to
"Default".Supported types are:
Default,End Effector,Manipulator,Humanoid,Wheeled,Holonomic,Quadruped,Mobile Manipulators,Aerial. Forwarded toMJCFImporterConfig.
- override_gain_type: str | None#
MuJoCo actuator gain type override (e.g.
"fixed"). Defaults toNone.Noneleaves the value parsed from the MJCF file unchanged. Seeisaacsim.asset.importer.utils.impl.asset_utils.apply_mjc_actuator_gains()for the supported encodings.
- override_bias_type: str | None#
MuJoCo actuator bias type override (e.g.
"affine"). Defaults toNone.Noneleaves the value parsed from the MJCF file unchanged.
- override_gain_prm: list[float] | None#
MuJoCo actuator gain parameter array override. Defaults to
None.Mujoco models actuators using an affine transformation, which is a linear combination of the gain parameters, control, and bias.
The affine transformation is defined as: tau = gain @ control + bias
Noneleaves the value parsed from the MJCF file unchanged. Example for position control:[kp, 0, 0, 0, 0, 0, 0, 0, 0, 0].
- override_bias_prm: list[float] | None#
MuJoCo actuator bias parameter array override. Defaults to
None.Noneleaves the value parsed from the MJCF file unchanged. Example for position control:[0, -kp, -kd, 0, 0, 0, 0, 0, 0, 0].
- run_asset_transformer: bool#
Run the asset transformation profile to convert the flattened USD into a layered USD asset. Defaults to True.
After running this profile, the USD asset will be a layered USD asset with the following structure: - robot_name.usda (interface usd) - payloads/base.usda (base usd with links, meshes, and materials) - payloads/instances.usda (usd with visual and collision geometry) - payloads/geometry.usd (binary usd with meshes) - payloads/materials.usda (materials) - payloads/Physics/physics.usda (neutral physics format) - payloads/Physics/physX.usda (PhysX attributes) - payloads/Physics/mujoco.usda (MuJoCo attributes)