Skip to content
117 changes: 110 additions & 7 deletions docs/source/how-to/import_new_asset.rst
Original file line number Diff line number Diff line change
Expand Up @@ -46,11 +46,12 @@ is then passed to the :class:`~sim.converters.UrdfConverter` class.
The URDF importer has various configuration parameters that can be set to control the behavior of the importer.
The default values for the importer's configuration parameters are specified are in the :class:`~sim.converters.UrdfConverterCfg` class, and they are listed below. We made a few commonly modified settings to be available as command-line arguments when calling the ``convert_urdf.py``, and they are marked with ``*`` in the list. For a comprehensive list of the configuration parameters, please check the the documentation at `URDF importer`_.

Articulation and joint structure
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* :attr:`~sim.converters.UrdfConverterCfg.fix_base` * - Whether to fix the base of the robot.
This depends on whether you have a floating-base or fixed-base robot. The command-line flag is
``--fix-base`` where when set, the importer will fix the base of the robot, otherwise it will default to floating-base.
* :attr:`~sim.converters.UrdfConverterCfg.root_link_name` - The link on which the PhysX articulation root is placed.
**Deprecated in URDF importer 3.0** — this option is ignored.
* :attr:`~sim.converters.UrdfConverterCfg.merge_fixed_joints` * - Whether to merge the fixed joints.
Usually, this should be set to ``True`` to reduce the asset complexity. The command-line flag is
``--merge-joints`` where when set, the importer will merge the fixed joints, otherwise it will default to not merging the fixed joints.
Expand All @@ -65,10 +66,53 @@ The default values for the importer's configuration parameters are specified are
We support two ways to set the gains:

* :attr:`~sim.converters.UrdfConverterCfg.JointDriveCfg.PDGainsCfg` - To directly set the stiffness and damping.
Both ``stiffness`` and ``damping`` accept a single float (applied uniformly).
* :attr:`~sim.converters.UrdfConverterCfg.JointDriveCfg.NaturalFrequencyGainsCfg` - To set the gains using the
desired natural frequency response of the system. **Deprecated in URDF importer 3.0** — use
``PDGainsCfg`` instead.

Geometry, collisions, and materials
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* :attr:`~sim.converters.UrdfConverterCfg.collision_from_visuals` - Whether to create collision geometry
from visual geometry when no explicit ``<collision>`` is defined for a link. Defaults to ``False``.
* :attr:`~sim.converters.UrdfConverterCfg.collision_type` - The collision shape simplification to apply.
One of ``"Convex Hull"`` (default), ``"Convex Decomposition"``, ``"Bounding Sphere"``, or ``"Bounding Cube"``.
* :attr:`~sim.converters.UrdfConverterCfg.self_collision` - Whether to activate self-collisions between
links of the articulation. Defaults to ``False``.
* :attr:`~sim.converters.UrdfConverterCfg.merge_mesh` - Whether to merge meshes where possible to optimize
the model. Defaults to ``False``.
* :attr:`~sim.converters.UrdfConverterCfg.link_density` - Default density in ``kg/m^3`` for links whose
``<inertial>`` properties are missing. ``0.0`` (default) leaves densities unchanged.

Asset resolution and output
~~~~~~~~~~~~~~~~~~~~~~~~~~~

* :attr:`~sim.converters.UrdfConverterCfg.ros_package_paths` - List of ROS package name/path mappings used
to resolve ``package://`` URLs in the URDF. Each entry is a dict with keys ``name`` and ``path``.
* :attr:`~sim.converters.UrdfConverterCfg.robot_type` - Robot type applied by the USD robot schema.
Defaults to ``"Default"``. Must be one of: ``"Default"``, ``"End Effector"``, ``"Manipulator"``,
``"Humanoid"``, ``"Wheeled"``, ``"Holonomic"``, ``"Quadruped"``, ``"Mobile Manipulators"``, ``"Aerial"``.
* :attr:`~sim.converters.UrdfConverterCfg.run_asset_transformer` - Run the asset transformer to convert
the flattened USD into a layered USD (interface USD + payloads). Defaults to ``True``.
* :attr:`~sim.converters.UrdfConverterCfg.run_multi_physics_conversion` - Also emit MuJoCo-compatible joint
attributes alongside PhysX. Defaults to ``True``.
* :attr:`~sim.converters.UrdfConverterCfg.debug_mode` - Write intermediate conversion artifacts next to the
output USD for inspection. Defaults to ``False``.

Deprecated (no-op in URDF importer 3.0)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

The following options are retained for backwards compatibility but are ignored by the URDF importer 3.0.
A warning is logged when they are set.

* :attr:`~sim.converters.UrdfConverterCfg.root_link_name` - The link on which the PhysX articulation root
was previously placed.
* :attr:`~sim.converters.UrdfConverterCfg.convert_mimic_joints_to_normal_joints` - Convert mimic joints to
normal joints during conversion.
* :attr:`~sim.converters.UrdfConverterCfg.replace_cylinders_with_capsules` - Replace cylinder shapes with
capsule shapes during conversion.

For more detailed information on the configuration parameters, please check the documentation for :class:`~sim.converters.UrdfConverterCfg`.

Example Usage
Expand Down Expand Up @@ -139,6 +183,14 @@ is derived automatically from the robot name in the URDF):

* ``anymal.usda`` - This is the main asset file.

.. note::
The URDF importer auto-deduplicates the per-robot subdirectory when it already exists.
If you re-run the converter against the same ``usd_dir`` with a changed configuration
(for example, flipping ``fix_base``), the importer writes to a new numbered folder
(``anymal_1/``, ``anymal_2/``, …) rather than overwriting the previous output.
:attr:`~sim.converters.UrdfConverter.usd_path` reflects whichever folder the importer
actually used. Delete stale subdirectories manually (or wipe ``usd_dir``) if you do not
want them to accumulate on disk.

To run the script headless, you can add the ``--headless`` flag. This will not open the GUI and
exit the script after the conversion is complete.
Expand Down Expand Up @@ -169,22 +221,64 @@ parameters, please check the the documentation at `MJCF importer`_.

.. note::
The MJCF importer was rewritten in Isaac Sim 5.0 to use the ``mujoco-usd-converter`` library.
Settings such as ``fix_base``, ``import_sites``, ``import_inertia_tensor``, and ``make_instanceable``
are no longer needed — the converter now handles these automatically based on the MJCF file content.
Settings such as ``import_sites``, ``import_inertia_tensor``, and ``make_instanceable`` are no
longer needed — the converter now handles these automatically based on the MJCF file content.

Geometry, collisions, and materials
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

* :attr:`~sim.converters.MjcfConverterCfg.merge_mesh` * - Whether to merge meshes where possible to
optimize the model. The command-line flag is ``--merge-mesh``.
* :attr:`~sim.converters.MjcfConverterCfg.collision_from_visuals` * - Whether to generate collision
geometry from visual geometries. The command-line flag is ``--collision-from-visuals``.
* :attr:`~sim.converters.MjcfConverterCfg.collision_type` * - Type of collision geometry to use
(e.g. ``"default"``, ``"Convex Hull"``, ``"Convex Decomposition"``). The command-line flag is
``--collision-type``.
* :attr:`~sim.converters.MjcfConverterCfg.collision_type` * - The collision shape simplification to
apply. One of ``"Convex Hull"`` (default), ``"Convex Decomposition"``, ``"Bounding Sphere"``, or
``"Bounding Cube"``. The command-line flag is ``--collision-type``.
* :attr:`~sim.converters.MjcfConverterCfg.self_collision` * - Whether to activate self-collisions
between links of the articulation. The command-line flag is ``--self-collision``.

Articulation and physics
~~~~~~~~~~~~~~~~~~~~~~~~

* :attr:`~sim.converters.MjcfConverterCfg.fix_base` - Whether to add a fixed joint between the world
and the root rigid-body link. Defaults to ``False``.
* :attr:`~sim.converters.MjcfConverterCfg.link_density` - Default density in ``kg/m^3`` for links whose
``<inertial>`` properties are missing in the MJCF. ``0.0`` (default) leaves densities unchanged.
* :attr:`~sim.converters.MjcfConverterCfg.import_physics_scene` * - Import physics scene properties
(gravity, time step, etc.) from the MJCF file. Defaults to ``False``. The command-line flag is
``--import-physics-scene``.

Actuator overrides
~~~~~~~~~~~~~~~~~~

MuJoCo models actuators as an affine transformation ``tau = gain @ control + bias``. The following
options override the values parsed from the MJCF on a per-actuator basis. Each defaults to ``None``,
which leaves the parsed values unchanged.

* :attr:`~sim.converters.MjcfConverterCfg.override_gain_type` - The actuator gain type override (e.g.
``"fixed"``).
* :attr:`~sim.converters.MjcfConverterCfg.override_bias_type` - The actuator bias type override (e.g.
``"affine"``).
* :attr:`~sim.converters.MjcfConverterCfg.override_gain_prm` - The actuator gain parameter array override.
Example for position control: ``[kp, 0, 0, 0, 0, 0, 0, 0, 0, 0]``.
* :attr:`~sim.converters.MjcfConverterCfg.override_bias_prm` - The actuator bias parameter array override.
Example for position control: ``[0, -kp, -kd, 0, 0, 0, 0, 0, 0, 0]``.

Asset resolution and output
~~~~~~~~~~~~~~~~~~~~~~~~~~~

* :attr:`~sim.converters.MjcfConverterCfg.robot_type` - Robot type applied by the USD robot schema.
Defaults to ``"Default"``. Must be one of: ``"Default"``, ``"End Effector"``, ``"Manipulator"``,
``"Humanoid"``, ``"Wheeled"``, ``"Holonomic"``, ``"Quadruped"``, ``"Mobile Manipulators"``, ``"Aerial"``.
* :attr:`~sim.converters.MjcfConverterCfg.run_asset_transformer` - Run the asset transformer to convert
the flattened USD into a layered USD (interface USD + payloads). Defaults to ``True``.
* :attr:`~sim.converters.MjcfConverterCfg.run_multi_physics_conversion` - Convert compatible MuJoCo
attributes to PhysX attributes (e.g. actuator gains). Defaults to ``True``.
* :attr:`~sim.converters.MjcfConverterCfg.debug_mode` - Write intermediate conversion artifacts next to
the output USD for inspection. Defaults to ``False``.

For more detailed information on the configuration parameters, please check the documentation for :class:`~sim.converters.MjcfConverterCfg`.


Example Usage
~~~~~~~~~~~~~
Expand Down Expand Up @@ -234,6 +328,15 @@ Executing the above script will create the USD file inside the

* ``h1.usd`` - This is the converted USD asset file.

.. note::
The MJCF importer auto-deduplicates the per-robot subdirectory when it already exists,
matching the URDF importer's behavior. If you re-run the converter against the same
``usd_dir`` with a changed configuration, the importer writes to a new numbered folder
(``h1_1/``, ``h1_2/``, …) rather than overwriting the previous output.
:attr:`~sim.converters.MjcfConverter.usd_path` reflects whichever folder the importer
actually used. Delete stale subdirectories manually (or wipe ``usd_dir``) if you do not
want them to accumulate on disk.

.. figure:: ../_static/tutorials/tutorial_convert_mjcf.jpg
:align: center
:figwidth: 100%
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
Added
^^^^^
* Added :attr:`~isaaclab.sim.converters.UrdfConverterCfg.ros_package_paths`,
:attr:`~isaaclab.sim.converters.UrdfConverterCfg.robot_type`,
:attr:`~isaaclab.sim.converters.UrdfConverterCfg.run_asset_transformer`,
:attr:`~isaaclab.sim.converters.UrdfConverterCfg.run_multi_physics_conversion`, and
:attr:`~isaaclab.sim.converters.UrdfConverterCfg.debug_mode` config fields that mirror the
new :class:`isaacsim.asset.importer.urdf.URDFImporterConfig` options.
* Extended :attr:`~isaaclab.sim.converters.UrdfConverterCfg.collision_type` to accept
``"Bounding Sphere"`` and ``"Bounding Cube"`` in addition to the existing ``"Convex Hull"``
and ``"Convex Decomposition"`` values.
* Added :attr:`~isaaclab.sim.converters.MjcfConverterCfg.fix_base`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.link_density`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.robot_type`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.override_gain_type`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.override_bias_type`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.override_gain_prm`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.override_bias_prm`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.run_asset_transformer`,
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.run_multi_physics_conversion`, and
:attr:`~isaaclab.sim.converters.MjcfConverterCfg.debug_mode` config fields that mirror the
new :class:`isaacsim.asset.importer.mjcf.MJCFImporterConfig` options.

Changed
^^^^^^^
* Refactored :class:`~isaaclab.sim.converters.UrdfConverter` to delegate the full conversion
pipeline to :class:`isaacsim.asset.importer.urdf.URDFImporter` /
:class:`isaacsim.asset.importer.urdf.URDFImporterConfig`. The duplicated IsaacLab
implementations of ``_apply_fix_base``, ``_apply_link_density``, ``_apply_joint_drives``,
``_set_drive_type_on_joints``, ``_set_target_type_on_joints``, ``_set_drive_gains_on_joints``,
and ``_fix_articulation_root_for_fixed_base`` have been removed and replaced with a thin
translation layer that maps :class:`~isaaclab.sim.converters.UrdfConverterCfg` onto the
Isaac Sim importer config. All behaviour is preserved.
* Updated :class:`~isaaclab.sim.converters.MjcfConverter` to forward the full set of
:class:`isaacsim.asset.importer.mjcf.MJCFImporterConfig` options to the Isaac Sim importer.

Removed
^^^^^^^
* Removed :func:`~isaaclab.sim.converters.urdf_utils.merge_fixed_joints` as it is now handled by the Isaac Sim URDF importer.
47 changes: 24 additions & 23 deletions source/isaaclab/isaaclab/sim/converters/mjcf_converter.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,12 @@
class MjcfConverter(AssetConverterBase):
"""Converter 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. It uses the :class:`MJCFImporter` class and :class:`MJCFImporterConfig`
dataclass from Isaac Sim to perform the conversion.
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 :class:`~isaacsim.asset.importer.mjcf.MJCFImporter` — this class
only translates :class:`MjcfConverterCfg` into a flat
:class:`~isaacsim.asset.importer.mjcf.MJCFImporterConfig`.

.. caution::
The current lazy conversion implementation does not automatically trigger USD generation if
Expand Down Expand Up @@ -44,43 +47,41 @@ def __init__(self, cfg: MjcfConverterCfg):
Args:
cfg: The configuration instance for MJCF to USD conversion.
"""
# The new MJCF importer outputs to: {usd_path}/{robot_name}/{robot_name}.usda
# Pre-adjust usd_file_name to match this output structure so that lazy conversion works correctly.
# The MJCF importer outputs to: {usd_path}/{robot_name}/{robot_name}.usda
# Pre-adjust `usd_file_name` to match this output structure so that lazy conversion works correctly.
file_basename = os.path.splitext(os.path.basename(cfg.asset_path))[0]
cfg.usd_file_name = os.path.join(file_basename, f"{file_basename}.usda")
super().__init__(cfg=cfg)

"""
Implementation specific methods.
"""

def _convert_asset(self, cfg: MjcfConverterCfg):
"""Calls underlying Isaac Sim MJCFImporter to convert MJCF to USD.
"""Run the Isaac Sim MJCF importer pipeline.

Args:
cfg: The configuration instance for MJCF to USD conversion.
"""
import shutil

from isaacsim.asset.importer.mjcf import MJCFImporter, MJCFImporterConfig

# Clean up existing output subdirectory so the importer writes fresh files.
# The MJCFImporter outputs to {usd_dir}/{robot_name}/{robot_name}.usda and may
# skip writing if the output already exists from a previous conversion.
file_basename = os.path.splitext(os.path.basename(cfg.asset_path))[0]
output_subdir = os.path.join(self.usd_dir, file_basename)
if os.path.exists(output_subdir):
shutil.rmtree(output_subdir)

import_config = MJCFImporterConfig(
mjcf_path=cfg.asset_path,
usd_path=self.usd_dir,
import_scene=cfg.import_physics_scene,
merge_mesh=cfg.merge_mesh,
collision_from_visuals=cfg.collision_from_visuals,
collision_type=cfg.collision_type,
allow_self_collision=cfg.self_collision,
import_scene=cfg.import_physics_scene,
robot_type=cfg.robot_type,
fix_base=cfg.fix_base,
link_density=cfg.link_density if cfg.link_density > 0.0 else None,
override_gain_type=cfg.override_gain_type,
override_bias_type=cfg.override_bias_type,
override_gain_prm=cfg.override_gain_prm,
override_bias_prm=cfg.override_bias_prm,
run_asset_transformer=cfg.run_asset_transformer,
run_multi_physics_conversion=cfg.run_multi_physics_conversion,
debug_mode=cfg.debug_mode,
)

importer = MJCFImporter(import_config)
importer.import_mjcf()
generated_usd_path = MJCFImporter(import_config).import_mjcf()
if generated_usd_path:
generated_usd_path = os.path.normpath(generated_usd_path)
self._usd_file_name = os.path.relpath(generated_usd_path, self.usd_dir)
Loading
Loading