From 84436b3161353b98f8e544cb0a6683611b168334 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Fri, 24 Apr 2026 09:35:18 -0700 Subject: [PATCH 01/10] update urdf mjcf importer to use the latest isaac sim importer --- source/isaaclab/docs/CHANGELOG.rst | 46 +- .../isaaclab/sim/converters/mjcf_converter.py | 39 +- .../sim/converters/mjcf_converter_cfg.py | 105 +++- .../isaaclab/sim/converters/urdf_converter.py | 495 +++--------------- .../sim/converters/urdf_converter_cfg.py | 60 ++- .../isaaclab/sim/converters/urdf_utils.py | 351 +------------ .../isaaclab/test/sim/test_urdf_converter.py | 6 +- 7 files changed, 290 insertions(+), 812 deletions(-) diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 8cc881bae674..cd0d117281bb 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,49 @@ Changelog --------- +5.3.0 (2026-05-14) +~~~~~~~~~~~~~~~~~~~ + +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. + 5.2.0 (2026-05-14) ~~~~~~~~~~~~~~~~~~ @@ -119,7 +162,6 @@ Fixed installable alongside ``isaacsim==6.0.0.0``. Users who want the Viser visualizer can request it explicitly with ``isaaclab[viser]``. - 5.1.1 (2026-05-13) ~~~~~~~~~~~~~~~~~~ @@ -142,7 +184,6 @@ Fixed when Fabric is unavailable, with no impact on the cloning speedup when Fabric is present. - 5.1.0 (2026-05-12) ~~~~~~~~~~~~~~~~~~ @@ -192,7 +233,6 @@ Fixed * Fixed extension installation to honor ``pip_upgrade_dependencies`` declared in ``config/extension.toml``. - 5.0.0 (2026-05-11) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py index 2c8fe992a35a..ca3d5dd18e21 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py @@ -6,6 +6,7 @@ from __future__ import annotations import os +import shutil from .asset_converter_base import AssetConverterBase from .mjcf_converter_cfg import MjcfConverterCfg @@ -14,9 +15,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 @@ -44,8 +48,8 @@ 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) @@ -55,18 +59,16 @@ def __init__(self, cfg: MjcfConverterCfg): """ 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. + # Clean up any existing output subdirectory so the importer writes fresh files. + # 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): @@ -75,12 +77,21 @@ def _convert_asset(self, cfg: MjcfConverterCfg): 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() + MJCFImporter(import_config).import_mjcf() diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py index a9dbe620c7da..18fa7ac53800 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py @@ -3,6 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + +from typing import Literal + from isaaclab.sim.converters.asset_converter_base_cfg import AssetConverterBaseCfg from isaaclab.utils import configclass @@ -11,31 +15,114 @@ class MjcfConverterCfg(AssetConverterBaseCfg): """The configuration class for MjcfConverter. - .. note:: - From Isaac Sim 5.0 onwards, the MJCF importer was rewritten to use the ``mujoco-usd-converter`` - library. Several settings from the old importer (``fix_base``, ``link_density``, - ``import_inertia_tensor``, ``import_sites``) are no longer available as they are handled - automatically by the converter based on the MJCF file content. + Maps to :class:`~isaacsim.asset.importer.mjcf.MJCFImporterConfig` from 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:: - The :attr:`~AssetConverterBaseCfg.make_instanceable` setting from the base class is not - supported by the new MJCF importer and will be ignored. + From Isaac Sim 5.0 onwards, the MJCF importer was rewritten to use the + ``mujoco-usd-converter`` library. The :attr:`AssetConverterBaseCfg.make_instanceable` + setting from the base class is not supported by the new MJCF importer and is ignored. """ + # --------------------------------------------------------------- + # Geometry / mesh options + # --------------------------------------------------------------- + merge_mesh: bool = False """Merge meshes where possible to optimize the model. Defaults to False.""" collision_from_visuals: bool = False """Generate collision geometry from visual geometries. Defaults to False.""" - collision_type: str = "Convex Hull" + collision_type: Literal["Convex Hull", "Convex Decomposition", "Bounding Sphere", "Bounding Cube"] = "Convex Hull" """Type of collision geometry to use. Defaults to ``"Convex Hull"``. - Supported values are ``"Convex Hull"``, and ``"Convex Decomposition"``. + Supported values match the ``collision_type`` field of + :class:`~isaacsim.asset.importer.mjcf.MJCFImporterConfig`. """ self_collision: bool = False """Activate self-collisions between links of the articulation. Defaults to False.""" + # --------------------------------------------------------------- + # Physics / articulation options + # --------------------------------------------------------------- + import_physics_scene: bool = False """Import the physics scene (time step per second, gravity, etc.) from the MJCF file. Defaults to False.""" + + fix_base: bool = False + """Add a fixed joint from the world to the root rigid-body link. Defaults to False. + + When enabled, :class:`~isaacsim.asset.importer.mjcf.MJCFImporter` inserts a ``FixedJoint`` + between the world and the articulation root and relocates ``ArticulationRootAPI`` onto the + appropriate ancestor prim so PhysX treats the articulation as fixed-base. + """ + + link_density: float = 0.0 + """Default density in ``kg/m^3`` for links whose ``"inertial"`` properties are missing. + Defaults to 0.0. + + A value of ``0.0`` leaves density unchanged. + """ + + robot_type: str = "Default" + """Robot type applied by the USD robot schema. Defaults to ``"Default"``. + + Forwarded to :class:`~isaacsim.asset.importer.mjcf.MJCFImporterConfig`. + """ + + # --------------------------------------------------------------- + # Actuator gain overrides + # --------------------------------------------------------------- + + override_gain_type: str | None = None + """MuJoCo actuator gain type override (e.g. ``"fixed"``). Defaults to ``None``. + + ``None`` leaves the value parsed from the MJCF file unchanged. See + :func:`isaacsim.asset.importer.utils.impl.asset_utils.apply_mjc_actuator_gains` for + the supported encodings. + """ + + override_bias_type: str | None = None + """MuJoCo actuator bias type override (e.g. ``"affine"``). Defaults to ``None``. + + ``None`` leaves the value parsed from the MJCF file unchanged. + """ + + override_gain_prm: list[float] | None = None + """MuJoCo actuator gain parameter array (10 floats) override. Defaults to ``None``. + + ``None`` leaves 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 = None + """MuJoCo actuator bias parameter array (10 floats) override. Defaults to ``None``. + + ``None`` leaves the value parsed from the MJCF file unchanged. Example for position + control: ``[0, -kp, -kd, 0, 0, 0, 0, 0, 0, 0]``. + """ + + # --------------------------------------------------------------- + # Importer pipeline options + # --------------------------------------------------------------- + + run_asset_transformer: bool = True + """Whether to run the asset transformer profile after conversion. Defaults to True. + + When enabled, the importer restructures the intermediate USD into a layered, + payload-based package. Disable for a single flat USD output. + """ + + run_multi_physics_conversion: bool = True + """Whether to run the MJCF-to-PhysX physics conversion pass. Defaults to True.""" + + debug_mode: bool = False + """Enable debug mode in the underlying MJCF importer. Defaults to False. + + When enabled, the importer writes intermediate conversion artifacts next to the output + USD for inspection instead of using a temporary scratch directory. + """ diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py index a2c41483a46f..4f72363b8a17 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py @@ -5,15 +5,8 @@ from __future__ import annotations -import contextlib -import gc -import importlib -import math import os import pathlib -import re -import shutil -import tempfile import carb import omni.kit.app @@ -25,9 +18,15 @@ class UrdfConverter(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. + 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 + :class:`~isaacsim.asset.importer.urdf.URDFImporter` together with + :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig`. IsaacLab only translates its + user-friendly :class:`UrdfConverterCfg` into the flat importer config. .. caution:: The current lazy conversion implementation does not automatically trigger USD generation if @@ -45,11 +44,6 @@ class UrdfConverter(AssetConverterBase): ``replace_cylinders_with_capsules`` are no longer natively supported by the importer and will emit warnings if enabled. - .. note:: - The ``merge_fixed_joints`` feature is implemented as a URDF XML pre-processing step that - runs *before* the USD conversion. It removes fixed joints from the URDF and merges the - child link's visual, collision, and inertial elements into the parent link. - .. _isaacsim.asset.importer.urdf: https://docs.isaacsim.omniverse.nvidia.com/latest/importer_exporter/ext_isaacsim_asset_importer_urdf.html """ @@ -67,7 +61,7 @@ def __init__(self, cfg: UrdfConverterCfg): if not manager.is_extension_enabled("isaacsim.asset.importer.urdf"): manager.set_extension_enabled_immediate("isaacsim.asset.importer.urdf", True) - # set `usd_file_name` to match the new importer's output path structure: + # set `usd_file_name` to match the importer's output path structure: # the importer generates `{usd_path}/{robot_name}/{robot_name}.usda` robot_name = pathlib.PurePath(cfg.asset_path).stem cfg.usd_file_name = os.path.join(robot_name, f"{robot_name}.usda") @@ -79,124 +73,47 @@ def __init__(self, cfg: UrdfConverterCfg): """ def _convert_asset(self, cfg: UrdfConverterCfg): - """Calls the URDF importer 3.0 pipeline to convert URDF to USD. + """Run the Isaac Sim URDF importer pipeline. - This method replicates the ``URDFImporter.import_urdf()`` pipeline from the - ``isaacsim.asset.importer.urdf`` extension, inserting IsaacLab-specific post-processing - (fix base, joint drives, link density) on the intermediate stage before the asset - transformer restructures the output. + Translates :class:`UrdfConverterCfg` into a flat + :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig` and invokes + :meth:`~isaacsim.asset.importer.urdf.URDFImporter.import_urdf`. The importer handles + fixed-joint merging, fix-base insertion, joint-drive configuration, link density + overrides, and the asset transformer profile internally. Args: cfg: The URDF conversion configuration. """ - from isaacsim.asset.importer.utils.impl import importer_utils, stage_utils - from pxr import Sdf - - from .urdf_utils import merge_fixed_joints + from isaacsim.asset.importer.urdf import URDFImporter, URDFImporterConfig # log warnings for features no longer supported by the URDF importer 3.0 self._warn_unsupported_features(cfg) - urdf_path = os.path.normpath(cfg.asset_path) - robot_name = os.path.basename(urdf_path).split(".")[0] - usd_path = os.path.normpath(self.usd_dir) - - # step 0: optionally pre-process the URDF to merge fixed joints - # The merged file is written next to the original so that relative mesh paths - # (e.g. ``meshes/link.stl``) continue to resolve correctly. If the source - # directory is read-only, a temp directory is used as a fallback (relative mesh - # paths may not resolve in that case). - merged_urdf_path: str | None = None - if cfg.merge_fixed_joints: - urdf_dir = os.path.dirname(urdf_path) - try: - fd, merged_urdf_path = tempfile.mkstemp(suffix=".urdf", prefix=".merged_", dir=urdf_dir) - os.close(fd) - except OSError: - carb.log_warn( - "UrdfConverter: Cannot write merged URDF next to the original (read-only directory)." - " Falling back to a temp directory — relative mesh paths may not resolve." - ) - merged_urdf_dir = tempfile.mkdtemp(prefix="isaaclab_urdf_merge_") - merged_urdf_path = os.path.join(merged_urdf_dir, os.path.basename(urdf_path)) - merge_fixed_joints(urdf_path, merged_urdf_path) - urdf_path = merged_urdf_path - - usdex_path = os.path.normpath(os.path.join(usd_path, "usdex")) - intermediate_path = os.path.normpath(os.path.join(usd_path, "temp", f"{robot_name}.usd")) - - # step 1: convert URDF to intermediate USD using urdf-usd-converter - urdf_usd_converter = importlib.import_module("urdf_usd_converter") - converter = urdf_usd_converter.Converter(layer_structure=False, scene=False) - asset: Sdf.AssetPath = converter.convert(urdf_path, usdex_path) - - # step 2: open the intermediate stage and run standard post-processing - stage = stage_utils.open_stage(asset.path) - if not stage: - raise ValueError(f"Failed to open intermediate stage at path: {asset.path}") - - importer_utils.remove_custom_scopes(stage) - importer_utils.add_rigid_body_schemas(stage) - importer_utils.add_joint_schemas(stage) - - # step 3: apply optional importer features - if cfg.collision_from_visuals: - importer_utils.collision_from_visuals(stage, cfg.collision_type) - - importer_utils.enable_self_collision(stage, cfg.self_collision) - - # step 4: IsaacLab-specific post-processing on the intermediate stage - if cfg.fix_base: - self._apply_fix_base(stage) - - if cfg.link_density > 0: - self._apply_link_density(stage, cfg.link_density) - - if cfg.joint_drive: - self._apply_joint_drives(stage, cfg) - - # step 5: save the intermediate stage - stage_utils.save_stage(stage, intermediate_path) - stage = None - gc.collect() - - # step 6: run the asset transformer to produce the final structured output - ext_manager = omni.kit.app.get_app().get_extension_manager() - ext_id = ext_manager.get_enabled_extension_id("isaacsim.asset.transformer.rules") - extension_path = ext_manager.get_extension_path(ext_id) - asset_structure_profile_json_path = os.path.normpath( - os.path.abspath(os.path.join(extension_path, "data", "isaacsim_structure.json")) - ) - - importer_utils.run_asset_transformer_profile( - input_stage_path=intermediate_path, - output_package_root=os.path.normpath(os.path.join(usd_path, robot_name)), - profile_json_path=asset_structure_profile_json_path, + # translate nested `JointDriveCfg` into flat importer fields + drive_type, target_type, stiffness, damping = self._unpack_joint_drive(cfg.joint_drive) + + import_config = URDFImporterConfig( + urdf_path=os.path.normpath(cfg.asset_path), + usd_path=os.path.normpath(self.usd_dir), + merge_fixed_joints=cfg.merge_fixed_joints, + merge_mesh=cfg.merge_mesh, + collision_from_visuals=cfg.collision_from_visuals, + collision_type=cfg.collision_type, + allow_self_collision=cfg.self_collision, + ros_package_paths=list(cfg.ros_package_paths), + robot_type=cfg.robot_type, + fix_base=cfg.fix_base, + link_density=cfg.link_density if cfg.link_density > 0.0 else None, + joint_drive_type=drive_type, + joint_target_type=target_type, + override_joint_stiffness=stiffness, + override_joint_damping=damping, + run_asset_transformer=cfg.run_asset_transformer, + run_multi_physics_conversion=cfg.run_multi_physics_conversion, + debug_mode=cfg.debug_mode, ) - # step 6b: fix ArticulationRootAPI placement for fixed-base articulations. - # After the asset transformer, ArticulationRootAPI ends up on the root rigid body. - # Having a FixedJoint on the same rigid body that has ArticulationRootAPI causes - # PhysX to treat the articulation as a floating-base + constraint (maximal coordinate - # tree) rather than a fixed-base reduced-coordinate articulation. - # Moving ArticulationRootAPI to the parent of the root rigid body resolves this. - if cfg.fix_base: - final_usd_path = os.path.join(usd_path, robot_name, f"{robot_name}.usda") - self._fix_articulation_root_for_fixed_base(final_usd_path) - - # step 7: clean up intermediate files - if os.path.exists(usdex_path): - shutil.rmtree(usdex_path) - temp_dir = os.path.dirname(intermediate_path) - if os.path.exists(temp_dir): - shutil.rmtree(temp_dir) - if merged_urdf_path is not None: - with contextlib.suppress(OSError): - os.remove(merged_urdf_path) - # if we used a fallback temp directory, clean that up too - merged_parent = os.path.dirname(merged_urdf_path) - if merged_parent.startswith(tempfile.gettempdir()) and os.path.isdir(merged_parent): - shutil.rmtree(merged_parent, ignore_errors=True) + URDFImporter(import_config).import_urdf() """ Helper methods. @@ -236,319 +153,27 @@ def _warn_unsupported_features(cfg: UrdfConverterCfg): ) @staticmethod - def _apply_fix_base(stage): - """Add a fixed joint from the world to the root link of the robot. - - Args: - stage: The USD stage to modify. - """ - from pxr import UsdPhysics - - default_prim = stage.GetDefaultPrim() - if not default_prim or not default_prim.IsValid(): - carb.log_warn("UrdfConverter: Cannot apply fix_base - no default prim found.") - return - - # find the root link: first child with `RigidBodyAPI` under the prim hierarchy - root_link = None - for prim in stage.Traverse(): - if prim.HasAPI(UsdPhysics.RigidBodyAPI): - root_link = prim - break - - if root_link is None: - carb.log_warn("UrdfConverter: Cannot apply fix_base - no rigid body link found.") - return - - # create a fixed joint connecting the world to the root link - default_prim_path = default_prim.GetPath() - joint_path = default_prim_path.AppendChild("fix_base_joint") - - fixed_joint = UsdPhysics.FixedJoint.Define(stage, joint_path) - # `body0` left empty => connected to the world frame - fixed_joint.CreateBody1Rel().SetTargets([root_link.GetPath()]) - - @staticmethod - def _fix_articulation_root_for_fixed_base(usd_path: str): - """Move ArticulationRootAPI from the root rigid body to its parent prim. - - After the asset transformer, ArticulationRootAPI ends up on the root rigid body. - When combined with a FixedJoint on that same body (``fix_base_joint``), PhysX treats - the articulation as a floating-base + external constraint (maximal coordinate tree) - rather than a proper fixed-base reduced-coordinate articulation. - - Moving ArticulationRootAPI to the parent of the root rigid body (a non-rigid Xform / - Scope ancestor) resolves this, matching the pattern used by ``schemas.py``'s - ``fix_root_link``. - - Changes are authored as **local opinions in the root layer** of the stage, which are - stronger than the variant-payload-sublayer opinions written by the asset transformer. - This means the root layer's ``delete apiSchemas`` overrides the ``prepend apiSchemas`` - in the deeper sublayers without modifying those files. - - Args: - usd_path: Absolute path to the final ``.usda`` file produced by the asset transformer. - """ - from pxr import Usd, UsdPhysics - - stage = Usd.Stage.Open(usd_path) - if not stage: - carb.log_warn( - f"UrdfConverter: Cannot open final stage at '{usd_path}'" - " for fix_base ArticulationRootAPI post-processing." - ) - return - - # Find the root rigid body that incorrectly has ArticulationRootAPI applied. - root_body_prim = None - for prim in stage.Traverse(): - if prim.HasAPI(UsdPhysics.ArticulationRootAPI) and prim.HasAPI(UsdPhysics.RigidBodyAPI): - root_body_prim = prim - break - - if root_body_prim is None: - # ArticulationRootAPI is already on a non-rigid ancestor (correct) or not present. - return - - parent_prim = root_body_prim.GetParent() - if not parent_prim or not parent_prim.IsValid(): - carb.log_warn("UrdfConverter: Root rigid body has no valid parent prim — skipping ArticulationRootAPI fix.") - return - - # Collect all articulation-related schema names applied to the root rigid body. - articulation_api_names = [ - name - for name in root_body_prim.GetAppliedSchemas() - if "ArticulationRoot" in name or name == "PhysxArticulationAPI" - ] - - # --- Apply ArticulationRootAPI schemas to the parent prim --- - # (edit target is the root layer by default; writes local opinions) - UsdPhysics.ArticulationRootAPI.Apply(parent_prim) - already_on_parent = set(parent_prim.GetAppliedSchemas()) - for name in articulation_api_names: - if name != "PhysicsArticulationRootAPI" and name not in already_on_parent: - parent_prim.AddAppliedSchema(name) - - # --- Copy USD articulation attributes to the parent prim --- - usd_art_api = UsdPhysics.ArticulationRootAPI(root_body_prim) - for attr_name in usd_art_api.GetSchemaAttributeNames(): - attr = root_body_prim.GetAttribute(attr_name) - val = attr.Get() if attr else None - if val is not None: - parent_attr = parent_prim.GetAttribute(attr_name) - if not parent_attr: - parent_attr = parent_prim.CreateAttribute(attr_name, attr.GetTypeName()) - parent_attr.Set(val) - - # --- Copy physxArticulation:* attributes to the parent prim --- - for attr in root_body_prim.GetAttributes(): - aname = attr.GetName() - if aname.startswith("physxArticulation:"): - val = attr.Get() - if val is not None: - parent_attr = parent_prim.GetAttribute(aname) - if not parent_attr: - parent_attr = parent_prim.CreateAttribute(aname, attr.GetTypeName()) - parent_attr.Set(val) - - # --- Remove ArticulationRootAPI schemas from the root rigid body --- - # Writing "delete" list-ops in the root layer overrides "prepend" in sublayers. - root_body_prim.RemoveAppliedSchema("PhysxArticulationAPI") - root_body_prim.RemoveAPI(UsdPhysics.ArticulationRootAPI) - for name in articulation_api_names: - if name not in ("PhysicsArticulationRootAPI", "PhysxArticulationAPI"): - root_body_prim.RemoveAppliedSchema(name) - - # Save only the root layer (sublayers produced by the asset transformer are untouched). - stage.GetRootLayer().Save() - - @staticmethod - def _apply_link_density(stage, density: float): - """Set default density on rigid body links that have no explicit mass. - - Args: - stage: The USD stage to modify. - density: The density value in kg/m^3. - """ - from pxr import UsdPhysics - - for prim in stage.Traverse(): - if not prim.HasAPI(UsdPhysics.MassAPI): - continue - mass_api = UsdPhysics.MassAPI(prim) - # only set density if mass is not explicitly specified (0.0 means auto-compute) - mass_attr = mass_api.GetMassAttr() - if mass_attr and mass_attr.HasValue() and mass_attr.Get() > 0.0: - continue - density_attr = mass_api.GetDensityAttr() - if not density_attr: - density_attr = mass_api.CreateDensityAttr() - density_attr.Set(density) - - def _apply_joint_drives(self, stage, cfg: UrdfConverterCfg): - """Set joint drive properties (type, target, gains) on USD joints. + def _unpack_joint_drive(joint_drive: UrdfConverterCfg.JointDriveCfg | None) -> tuple: + """Translate an IsaacLab :class:`UrdfConverterCfg.JointDriveCfg` into flat importer fields. Args: - stage: The USD stage to modify. - cfg: The URDF converter configuration containing joint drive settings. - """ - from pxr import UsdPhysics - - # collect all joints with their metadata - joints: dict[str, tuple] = {} - for prim in stage.Traverse(): - if not (prim.IsA(UsdPhysics.RevoluteJoint) or prim.IsA(UsdPhysics.PrismaticJoint)): - continue - joint_name = prim.GetName() - is_revolute = prim.IsA(UsdPhysics.RevoluteJoint) - instance_name = "angular" if is_revolute else "linear" - joints[joint_name] = (prim, is_revolute, instance_name) - - if not joints: - return - - drive_cfg = cfg.joint_drive - - # apply drive type (force / acceleration) - self._set_drive_type_on_joints(joints, drive_cfg) - # apply target type (none / position / velocity) - self._set_target_type_on_joints(joints, drive_cfg) - # apply gains (stiffness / damping) - self._set_drive_gains_on_joints(joints, drive_cfg) - - # ------------------------------------------------------------------ - # Joint drive helpers - # ------------------------------------------------------------------ - - @staticmethod - def _set_drive_type_on_joints(joints: dict, drive_cfg: UrdfConverterCfg.JointDriveCfg): - """Set the drive type (force or acceleration) on joint prims. + joint_drive: The nested IsaacLab joint-drive configuration, or ``None``. - Args: - joints: Mapping of joint name → (prim, is_revolute, instance_name). - drive_cfg: The joint drive configuration. - """ - from pxr import UsdPhysics - - def _apply(prim, instance_name: str, drive_type: str): - drive = UsdPhysics.DriveAPI.Get(prim, instance_name) - type_attr = drive.GetTypeAttr() - if not type_attr: - type_attr = drive.CreateTypeAttr() - type_attr.Set(drive_type) - - if isinstance(drive_cfg.drive_type, str): - for _name, (prim, _is_rev, inst) in joints.items(): - _apply(prim, inst, drive_cfg.drive_type) - elif isinstance(drive_cfg.drive_type, dict): - for pattern, drive_type in drive_cfg.drive_type.items(): - matches = [n for n in joints if re.search(pattern, n)] - if not matches: - raise ValueError( - f"Joint name pattern '{pattern}' in drive_type config matched no joints." - f" Available joints: {list(joints.keys())}" - ) - for name in matches: - prim, _, inst = joints[name] - _apply(prim, inst, drive_type) - - @staticmethod - def _set_target_type_on_joints(joints: dict, drive_cfg: UrdfConverterCfg.JointDriveCfg): - """Set the target type (none, position, velocity) on joint prims. - - For ``"none"``, both stiffness and damping are zeroed out. - - Args: - joints: Mapping of joint name → (prim, is_revolute, instance_name). - drive_cfg: The joint drive configuration. - """ - from pxr import UsdPhysics - - def _apply(prim, instance_name: str, target_type: str): - drive = UsdPhysics.DriveAPI.Get(prim, instance_name) - if target_type == "none": - drive.GetStiffnessAttr().Set(0.0) - drive.GetDampingAttr().Set(0.0) - - if isinstance(drive_cfg.target_type, str): - for _name, (prim, _is_rev, inst) in joints.items(): - _apply(prim, inst, drive_cfg.target_type) - elif isinstance(drive_cfg.target_type, dict): - for pattern, target_type in drive_cfg.target_type.items(): - matches = [n for n in joints if re.search(pattern, n)] - if not matches: - raise ValueError( - f"Joint name pattern '{pattern}' in target_type config matched no joints." - f" Available joints: {list(joints.keys())}" - ) - for name in matches: - prim, _, inst = joints[name] - _apply(prim, inst, target_type) - - @staticmethod - def _set_drive_gains_on_joints(joints: dict, drive_cfg: UrdfConverterCfg.JointDriveCfg): - """Set stiffness and damping on joint drive APIs. - - For revolute joints the user-facing values (Nm/rad) are converted to the USD - convention (Nm/deg) by multiplying by ``pi / 180``. - - Args: - joints: Mapping of joint name → (prim, is_revolute, instance_name). - drive_cfg: The joint drive configuration. + Returns: + Tuple ``(drive_type, target_type, stiffness, damping)`` suitable for + :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig`. Entries are ``None`` when + the user did not request an override. """ - from pxr import UsdPhysics - - gains = drive_cfg.gains - if not isinstance(gains, UrdfConverterCfg.JointDriveCfg.PDGainsCfg): - return - - def _set_stiffness(prim, instance_name: str, is_revolute: bool, value: float): - drive = UsdPhysics.DriveAPI.Get(prim, instance_name) - usd_value = value * math.pi / 180.0 if is_revolute else value - stiffness_attr = drive.GetStiffnessAttr() - if not stiffness_attr: - stiffness_attr = drive.CreateStiffnessAttr() - stiffness_attr.Set(usd_value) - - def _set_damping(prim, instance_name: str, is_revolute: bool, value: float): - drive = UsdPhysics.DriveAPI.Get(prim, instance_name) - usd_value = value * math.pi / 180.0 if is_revolute else value - damping_attr = drive.GetDampingAttr() - if not damping_attr: - damping_attr = drive.CreateDampingAttr() - damping_attr.Set(usd_value) - - # --- stiffness --- - if isinstance(gains.stiffness, (float, int)): - for _name, (prim, is_rev, inst) in joints.items(): - _set_stiffness(prim, inst, is_rev, gains.stiffness) - elif isinstance(gains.stiffness, dict): - for pattern, stiffness in gains.stiffness.items(): - matches = [n for n in joints if re.search(pattern, n)] - if not matches: - raise ValueError( - f"Joint name pattern '{pattern}' in stiffness config matched no joints." - f" Available joints: {list(joints.keys())}" - ) - for name in matches: - prim, is_rev, inst = joints[name] - _set_stiffness(prim, inst, is_rev, stiffness) - - # --- damping --- - if gains.damping is None: - return - if isinstance(gains.damping, (float, int)): - for _name, (prim, is_rev, inst) in joints.items(): - _set_damping(prim, inst, is_rev, gains.damping) - elif isinstance(gains.damping, dict): - for pattern, damping in gains.damping.items(): - matches = [n for n in joints if re.search(pattern, n)] - if not matches: - raise ValueError( - f"Joint name pattern '{pattern}' in damping config matched no joints." - f" Available joints: {list(joints.keys())}" - ) - for name in matches: - prim, is_rev, inst = joints[name] - _set_damping(prim, inst, is_rev, damping) + if joint_drive is None: + return None, None, None, None + + gains = joint_drive.gains + if isinstance(gains, UrdfConverterCfg.JointDriveCfg.PDGainsCfg): + stiffness = gains.stiffness + damping = gains.damping + else: + # `NaturalFrequencyGainsCfg` is deprecated; leave gains unchanged. + stiffness = None + damping = None + + return joint_drive.drive_type, joint_drive.target_type, stiffness, damping diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py index feb13f61ff20..e06785dc4bb0 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py @@ -14,7 +14,13 @@ @configclass class UrdfConverterCfg(AssetConverterBaseCfg): - """The configuration class for UrdfConverter.""" + """The configuration class for UrdfConverter. + + Maps to :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig` from the Isaac Sim + URDF importer. IsaacLab exposes a user-friendly nested :class:`JointDriveCfg` that is + translated into the importer's flat ``joint_drive_type`` / ``joint_target_type`` / + ``override_joint_stiffness`` / ``override_joint_damping`` fields at conversion time. + """ @configclass class JointDriveCfg: @@ -102,11 +108,16 @@ class NaturalFrequencyGainsCfg: """The name of the root link. Defaults to None. If None, the root link will be set by PhysX. + + .. deprecated:: + This option is no longer supported by the URDF importer 3.0. A warning is logged if set. """ link_density: float = 0.0 """Default density in ``kg/m^3`` for links whose ``"inertial"`` properties are missing in the URDF. Defaults to 0.0. + + A value of ``0.0`` leaves density unchanged. """ merge_fixed_joints: bool = True @@ -115,7 +126,8 @@ class NaturalFrequencyGainsCfg: 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. + consecutive fixed joints are handled automatically. The pre-processing is performed by + :func:`isaacsim.asset.importer.urdf.impl.urdf_utils.merge_fixed_joints`. """ convert_mimic_joints_to_normal_joints: bool = False @@ -128,19 +140,23 @@ class NaturalFrequencyGainsCfg: joint_drive: JointDriveCfg | None = JointDriveCfg() """The joint drive settings. Defaults to :class:`JointDriveCfg`. - The parameter can be set to ``None`` for URDFs without joints. + The parameter can be set to ``None`` for URDFs without joints, in which case no joint drive + overrides are sent to the importer. """ - collision_from_visuals = False + collision_from_visuals: bool = False """Whether to create collision geometry from visual geometry. Defaults to False.""" - collision_type: Literal["Convex Hull", "Convex Decomposition"] = "Convex Hull" - """The collision shape simplification. Defaults to "convex_hull". + collision_type: Literal["Convex Hull", "Convex Decomposition", "Bounding Sphere", "Bounding Cube"] = "Convex Hull" + """The collision shape simplification. Defaults to ``"Convex Hull"``. - Supported values are: + Supported values match the ``collision_type`` field of + :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig`: * ``"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 = False @@ -155,3 +171,33 @@ class NaturalFrequencyGainsCfg: merge_mesh: bool = False """Merge meshes where possible to optimize the model. Defaults to False.""" + + 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 ``name`` and ``path``. The list is forwarded directly + to :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig`. + """ + + robot_type: str = "Default" + """Robot type applied by the USD robot schema. Defaults to ``"Default"``. + + Forwarded to :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig`. + """ + + run_asset_transformer: bool = True + """Whether to run the asset transformer profile after conversion. Defaults to True. + + When enabled, the importer restructures the intermediate USD into a layered, + payload-based package. Disable for a single flat USD output. + """ + + run_multi_physics_conversion: bool = True + """Whether to run the URDF-to-PhysX joint attribute conversion pass. Defaults to True.""" + + debug_mode: bool = False + """Enable debug mode in the underlying URDF importer. Defaults to False. + + When enabled, the importer writes intermediate conversion artifacts next to the output + USD for inspection instead of using a temporary scratch directory. + """ diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_utils.py b/source/isaaclab/isaaclab/sim/converters/urdf_utils.py index dfef1ee01e52..2541212eae0c 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_utils.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_utils.py @@ -3,348 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Utility functions for pre-processing URDF files before USD conversion.""" +"""Backwards-compatible re-exports for URDF pre-processing utilities. -from __future__ import annotations - -import math -import xml.etree.ElementTree as ET - -import numpy as np - - -def merge_fixed_joints(urdf_path: str, output_path: str) -> str: - """Pre-process a URDF file to merge links connected by fixed joints. - - For each fixed joint, the child link's ````, ````, and ```` - elements are merged into the parent link with proper transform composition. Any - downstream joints whose parent was the child link are re-parented to the surviving - parent link (with their origin transforms composed accordingly). - - Chains of consecutive fixed joints are handled by iterating until no fixed joints - remain. - - Args: - urdf_path: Path to the input URDF file. - output_path: Path to write the modified URDF file. - - Returns: - The *output_path* that was written to. - """ - tree = ET.parse(urdf_path) - root = tree.getroot() - - # iterate until no fixed joints remain (handles chains) - while True: - fixed_joints = [j for j in root.findall("joint") if j.get("type") == "fixed"] - if not fixed_joints: - break - - # process the first fixed joint found (order matters for chains) - joint = fixed_joints[0] - parent_link_name = joint.find("parent").get("link") - child_link_name = joint.find("child").get("link") - - T_joint = _parse_origin(joint.find("origin")) - - # locate the corresponding `` elements - parent_link_elem = _find_link(root, parent_link_name) - child_link_elem = _find_link(root, child_link_name) - - if parent_link_elem is None or child_link_elem is None: - # safety guard: drop the joint and continue - root.remove(joint) - continue - - # move `` elements from child to parent (with composed transforms) - for visual in child_link_elem.findall("visual"): - _compose_origin(visual, T_joint) - parent_link_elem.append(visual) - - # move `` elements from child to parent (with composed transforms) - for collision in child_link_elem.findall("collision"): - _compose_origin(collision, T_joint) - parent_link_elem.append(collision) - - # merge `` properties (mass, CoM, inertia tensor) - _merge_inertial(parent_link_elem, child_link_elem, T_joint) - - # re-parent any joints that reference the child link as their parent - for other_joint in root.findall("joint"): - if other_joint is joint: - continue - parent_elem = other_joint.find("parent") - if parent_elem is not None and parent_elem.get("link") == child_link_name: - parent_elem.set("link", parent_link_name) - # compose transforms: new_origin = T_joint @ T_other - T_other = _parse_origin(other_joint.find("origin")) - _set_origin(other_joint, T_joint @ T_other) - - # remove the fixed joint and the now-empty child link - root.remove(joint) - root.remove(child_link_elem) - - tree.write(output_path, xml_declaration=True, encoding="UTF-8") - return output_path - - -# --------------------------------------------------------------------------- -# Transform helpers -# --------------------------------------------------------------------------- - - -def _parse_origin(origin_elem: ET.Element | None) -> np.ndarray: - """Parse an ```` element into a 4x4 homogeneous transform matrix. - - Args: - origin_elem: The ```` XML element (may be ``None``). - - Returns: - A 4x4 numpy array representing the transform. - """ - if origin_elem is None: - return np.eye(4) - xyz = [float(v) for v in origin_elem.get("xyz", "0 0 0").split()] - rpy = [float(v) for v in origin_elem.get("rpy", "0 0 0").split()] - return _make_transform(xyz, rpy) - - -def _make_transform(xyz: list[float], rpy: list[float]) -> np.ndarray: - """Create a 4x4 homogeneous transform from *xyz* translation and *rpy* rotation. - - Args: - xyz: Translation ``[x, y, z]``. - rpy: Euler angles ``[roll, pitch, yaw]`` in radians (URDF convention: ``Rz @ Ry @ Rx``). - - Returns: - A 4x4 numpy array. - """ - T = np.eye(4) - T[:3, :3] = _rpy_to_rotation_matrix(rpy) - T[:3, 3] = xyz - return T - - -def _rpy_to_rotation_matrix(rpy: list[float]) -> np.ndarray: - """Convert roll-pitch-yaw to a 3x3 rotation matrix (``Rz @ Ry @ Rx``). - - Args: - rpy: Euler angles ``[roll, pitch, yaw]`` in radians. - - Returns: - A 3x3 rotation matrix. - """ - roll, pitch, yaw = rpy - cr, sr = math.cos(roll), math.sin(roll) - cp, sp = math.cos(pitch), math.sin(pitch) - cy, sy = math.cos(yaw), math.sin(yaw) - return np.array( - [ - [cy * cp, cy * sp * sr - sy * cr, cy * sp * cr + sy * sr], - [sy * cp, sy * sp * sr + cy * cr, sy * sp * cr - cy * sr], - [-sp, cp * sr, cp * cr], - ] - ) - - -def _rotation_matrix_to_rpy(R: np.ndarray) -> tuple[float, float, float]: - """Convert a 3x3 rotation matrix to roll-pitch-yaw. - - Args: - R: A 3x3 rotation matrix. +Historically, IsaacLab shipped its own copy of ``merge_fixed_joints`` for the URDF +pipeline. That logic has moved to the Isaac Sim URDF importer at +:mod:`isaacsim.asset.importer.urdf.impl.urdf_utils`, so this module now simply re-exports +the canonical implementation to preserve the public import path +``isaaclab.sim.converters.urdf_utils``. +""" - Returns: - Tuple ``(roll, pitch, yaw)`` in radians. - """ - sy = -R[2, 0] - if abs(sy) >= 1.0 - 1e-12: - # gimbal lock - pitch = math.copysign(math.pi / 2, sy) - roll = math.atan2(R[0, 1], R[0, 2]) - yaw = 0.0 - else: - pitch = math.asin(np.clip(sy, -1.0, 1.0)) - roll = math.atan2(R[2, 1], R[2, 2]) - yaw = math.atan2(R[1, 0], R[0, 0]) - return (roll, pitch, yaw) - - -def _set_origin(element: ET.Element, T: np.ndarray) -> None: - """Set or create the ```` sub-element of *element* from a 4x4 transform. - - Args: - element: The parent XML element (e.g. ````, ````). - T: The 4x4 homogeneous transform. - """ - xyz = T[:3, 3] - rpy = _rotation_matrix_to_rpy(T[:3, :3]) - - origin = element.find("origin") - if origin is None: - origin = ET.SubElement(element, "origin") - - origin.set("xyz", f"{_fmt(xyz[0])} {_fmt(xyz[1])} {_fmt(xyz[2])}") - origin.set("rpy", f"{_fmt(rpy[0])} {_fmt(rpy[1])} {_fmt(rpy[2])}") - - -def _compose_origin(element: ET.Element, T_parent: np.ndarray) -> None: - """Compose *element*'s ```` with *T_parent* (``T_parent @ T_element``). - - The composed transform replaces the element's existing origin. - - Args: - element: An XML element that may contain an ```` child. - T_parent: The parent transform to prepend. - """ - T_elem = _parse_origin(element.find("origin")) - _set_origin(element, T_parent @ T_elem) - - -def _find_link(root: ET.Element, name: str) -> ET.Element | None: - """Find a ```` element by its ``name`` attribute. - - Args: - root: The ```` root element. - name: Link name to search for. - - Returns: - The matching ```` element, or ``None``. - """ - for link in root.findall("link"): - if link.get("name") == name: - return link - return None - - -def _fmt(v: float) -> str: - """Format a float for URDF output, suppressing near-zero noise. - - Args: - v: The value to format. - - Returns: - A string representation. - """ - if abs(v) < 1e-12: - return "0" - return f"{v:.10g}" - - -# --------------------------------------------------------------------------- -# Inertial merge -# --------------------------------------------------------------------------- - - -def _parse_inertia_matrix(inertia_elem: ET.Element | None) -> np.ndarray: - """Parse an ```` element into a 3x3 symmetric inertia matrix. - - Args: - inertia_elem: The ```` XML element (may be ``None``). - - Returns: - A 3x3 numpy array. - """ - if inertia_elem is None: - return np.zeros((3, 3)) - ixx = float(inertia_elem.get("ixx", "0")) - ixy = float(inertia_elem.get("ixy", "0")) - ixz = float(inertia_elem.get("ixz", "0")) - iyy = float(inertia_elem.get("iyy", "0")) - iyz = float(inertia_elem.get("iyz", "0")) - izz = float(inertia_elem.get("izz", "0")) - return np.array( - [ - [ixx, ixy, ixz], - [ixy, iyy, iyz], - [ixz, iyz, izz], - ] - ) - - -def _merge_inertial(parent_link: ET.Element, child_link: ET.Element, T_joint: np.ndarray) -> None: - """Merge the child link's inertial properties into the parent link. - - Uses the parallel axis theorem to correctly combine mass, center of mass, and - inertia tensors when the two bodies are rigidly attached. - - Args: - parent_link: The parent ```` element that will absorb the child. - child_link: The child ```` element being merged. - T_joint: The 4x4 transform from parent link frame to child link frame. - """ - child_inertial = child_link.find("inertial") - if child_inertial is None: - return # nothing to merge - - child_mass_elem = child_inertial.find("mass") - child_mass = float(child_mass_elem.get("value", "0")) if child_mass_elem is not None else 0.0 - if child_mass == 0.0: - return # zero mass — nothing to merge - - # -- child inertial in parent link frame -- - T_child_inertial = _parse_origin(child_inertial.find("origin")) - T_child_in_parent = T_joint @ T_child_inertial - R_child = T_child_in_parent[:3, :3] - child_com_in_parent = T_child_in_parent[:3, 3] - - child_I_local = _parse_inertia_matrix(child_inertial.find("inertia")) - child_I_in_parent = R_child @ child_I_local @ R_child.T - - # -- parent inertial -- - parent_inertial = parent_link.find("inertial") - if parent_inertial is not None: - parent_mass_elem = parent_inertial.find("mass") - parent_mass = float(parent_mass_elem.get("value", "0")) if parent_mass_elem is not None else 0.0 - T_parent_inertial = _parse_origin(parent_inertial.find("origin")) - R_parent = T_parent_inertial[:3, :3] - parent_com = T_parent_inertial[:3, 3] - parent_I_local = _parse_inertia_matrix(parent_inertial.find("inertia")) - parent_I_in_link = R_parent @ parent_I_local @ R_parent.T - else: - parent_inertial = ET.SubElement(parent_link, "inertial") - parent_mass = 0.0 - parent_com = np.zeros(3) - parent_I_in_link = np.zeros((3, 3)) - - # -- combined mass and center of mass -- - total_mass = parent_mass + child_mass - if total_mass == 0.0: - return - combined_com = (parent_mass * parent_com + child_mass * child_com_in_parent) / total_mass - - # -- parallel axis theorem: shift each inertia tensor to the combined CoM -- - def _shift_inertia(I_at_com: np.ndarray, mass: float, com: np.ndarray, ref: np.ndarray) -> np.ndarray: - d = ref - com - return I_at_com + mass * (np.dot(d, d) * np.eye(3) - np.outer(d, d)) - - parent_I_shifted = ( - _shift_inertia(parent_I_in_link, parent_mass, parent_com, combined_com) if parent_mass > 0 else parent_I_in_link - ) - child_I_shifted = _shift_inertia(child_I_in_parent, child_mass, child_com_in_parent, combined_com) - - combined_I = parent_I_shifted + child_I_shifted - - # -- write back to parent -- - # origin: combined CoM with identity rotation (tensor is already in link frame) - origin = parent_inertial.find("origin") - if origin is None: - origin = ET.SubElement(parent_inertial, "origin") - origin.set("xyz", f"{_fmt(combined_com[0])} {_fmt(combined_com[1])} {_fmt(combined_com[2])}") - origin.set("rpy", "0 0 0") +from __future__ import annotations - # mass - mass_elem = parent_inertial.find("mass") - if mass_elem is None: - mass_elem = ET.SubElement(parent_inertial, "mass") - mass_elem.set("value", f"{_fmt(total_mass)}") +from isaacsim.asset.importer.urdf.impl.urdf_utils import merge_fixed_joints - # inertia tensor - inertia_elem = parent_inertial.find("inertia") - if inertia_elem is None: - inertia_elem = ET.SubElement(parent_inertial, "inertia") - inertia_elem.set("ixx", _fmt(combined_I[0, 0])) - inertia_elem.set("ixy", _fmt(combined_I[0, 1])) - inertia_elem.set("ixz", _fmt(combined_I[0, 2])) - inertia_elem.set("iyy", _fmt(combined_I[1, 1])) - inertia_elem.set("iyz", _fmt(combined_I[1, 2])) - inertia_elem.set("izz", _fmt(combined_I[2, 2])) +__all__ = ["merge_fixed_joints"] diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 65c697029f97..9f29a1a446b9 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -636,9 +636,9 @@ def test_usd_structure_has_joints_and_links(sim_config): def test_link_density(sim_config): """Verify that link_density applies density to rigid body links. - Note: The Franka Panda URDF has explicit mass on all links, so ``_apply_link_density`` - only sets density on links without explicit mass (mass == 0). This test verifies the - pipeline runs without errors when link_density is set. + Note: The Franka Panda URDF has explicit mass on all links, so the importer's + ``apply_link_density`` only sets density on links without explicit mass (mass == 0). + This test verifies the pipeline runs without errors when ``link_density`` is set. """ sim, config = sim_config test_dir = os.path.dirname(os.path.abspath(__file__)) From fe2570f036c6635e23c59d67f28cdc30b97b9707 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Fri, 24 Apr 2026 09:57:45 -0700 Subject: [PATCH 02/10] update unit tests --- .../isaaclab/test/sim/test_mjcf_converter.py | 202 ++++++++++++++++++ .../isaaclab/test/sim/test_urdf_converter.py | 6 +- 2 files changed, 205 insertions(+), 3 deletions(-) diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 2e68b66a2fc0..548f68af8244 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -47,6 +47,7 @@ def test_setup_teardown(): yield sim, config # Teardown: Cleanup simulation + sim._disable_app_control_on_stop_handle = True # prevent timeout sim.stop() sim.clear_instance() @@ -97,3 +98,204 @@ def test_create_prim_from_usd(test_setup_teardown): sim_utils.create_prim(prim_path, usd_path=mjcf_converter.usd_path) assert sim.stage.GetPrimAtPath(prim_path).IsValid() + + +@pytest.mark.isaacsim_ci +def test_self_collision(test_setup_teardown): + """Verify that ``self_collision=True`` enables self-collisions on the articulation.""" + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_self_collision") + os.makedirs(output_dir, exist_ok=True) + + config.self_collision = True + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + from pxr import PhysxSchema, Usd + + stage = Usd.Stage.Open(mjcf_converter.usd_path) + found_self_collision = False + for prim in stage.Traverse(): + if prim.HasAPI(PhysxSchema.PhysxArticulationAPI): + physx_api = PhysxSchema.PhysxArticulationAPI(prim) + sc_attr = physx_api.GetEnabledSelfCollisionsAttr() + if sc_attr and sc_attr.HasValue() and sc_attr.Get(): + found_self_collision = True + break + + assert found_self_collision, "Expected self-collision to be enabled on the articulation" + + +@pytest.mark.isaacsim_ci +def test_collision_from_visuals(test_setup_teardown): + """Verify that ``collision_from_visuals=True`` runs successfully and produces a spawnable USD.""" + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_collision_visuals") + os.makedirs(output_dir, exist_ok=True) + + config.collision_from_visuals = True + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + assert os.path.exists(mjcf_converter.usd_path), "USD file should exist after conversion" + + prim_path = "/World/Robot" + sim_utils.create_prim(prim_path, usd_path=mjcf_converter.usd_path) + assert sim.stage.GetPrimAtPath(prim_path).IsValid() + + +@pytest.mark.isaacsim_ci +def test_collision_type_convex_decomposition(test_setup_teardown): + """Verify that ``collision_type='Convex Decomposition'`` runs without error.""" + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_convex_decomp") + os.makedirs(output_dir, exist_ok=True) + + config.collision_from_visuals = True + config.collision_type = "Convex Decomposition" + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + assert os.path.exists(mjcf_converter.usd_path), "USD file should exist after conversion" + + prim_path = "/World/Robot" + sim_utils.create_prim(prim_path, usd_path=mjcf_converter.usd_path) + assert sim.stage.GetPrimAtPath(prim_path).IsValid() + + +@pytest.mark.isaacsim_ci +def test_link_density(test_setup_teardown): + """Verify that ``link_density`` applies density without errors. + + ``nv_ant.xml`` has explicit inertial data on most bodies, so density is only applied where + mass is unspecified. This test ensures the pipeline runs and the output is spawnable. + """ + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_link_density") + os.makedirs(output_dir, exist_ok=True) + + config.link_density = 500.0 + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + from pxr import Usd, UsdPhysics + + stage = Usd.Stage.Open(mjcf_converter.usd_path) + mass_prims = [p for p in stage.Traverse() if p.HasAPI(UsdPhysics.MassAPI)] + assert len(mass_prims) > 0, "Expected prims with MassAPI" + + prim_path = "/World/Robot" + sim_utils.create_prim(prim_path, usd_path=mjcf_converter.usd_path) + assert sim.stage.GetPrimAtPath(prim_path).IsValid() + + +@pytest.mark.isaacsim_ci +def test_merge_mesh(test_setup_teardown): + """Verify that ``merge_mesh=True`` runs successfully and still produces a spawnable USD.""" + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_merge_mesh") + os.makedirs(output_dir, exist_ok=True) + + config.merge_mesh = True + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + assert os.path.exists(mjcf_converter.usd_path), "USD file should exist after conversion" + + prim_path = "/World/Robot" + sim_utils.create_prim(prim_path, usd_path=mjcf_converter.usd_path) + assert sim.stage.GetPrimAtPath(prim_path).IsValid() + + +@pytest.mark.isaacsim_ci +def test_import_physics_scene(test_setup_teardown): + """Verify that ``import_physics_scene=True`` still produces a spawnable USD.""" + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_physics_scene") + os.makedirs(output_dir, exist_ok=True) + + config.import_physics_scene = True + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + assert os.path.exists(mjcf_converter.usd_path), "USD file should exist after conversion" + + +@pytest.mark.isaacsim_ci +def test_run_asset_transformer_disabled(test_setup_teardown): + """Verify that ``run_asset_transformer=False`` produces a flat USD that is still spawnable.""" + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_no_transformer") + os.makedirs(output_dir, exist_ok=True) + + config.run_asset_transformer = False + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + assert os.path.exists(mjcf_converter.usd_path), "USD file should exist after conversion" + + prim_path = "/World/Robot" + sim_utils.create_prim(prim_path, usd_path=mjcf_converter.usd_path) + assert sim.stage.GetPrimAtPath(prim_path).IsValid() + + +@pytest.mark.isaacsim_ci +def test_override_actuator_gains(test_setup_teardown): + """Verify that actuator gain overrides are written to ``MjcActuator`` prims. + + ``nv_ant.xml`` defines ``MjcActuator`` prims, so setting ``override_gain_type``, + ``override_bias_type``, ``override_gain_prm``, and ``override_bias_prm`` should update the + corresponding ``mjc:*`` attributes on every actuator. + """ + sim, config = test_setup_teardown + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "mjcf_actuator_gains") + os.makedirs(output_dir, exist_ok=True) + + kp = 50.0 + kd = 5.0 + # canonical position-control encoding from the importer's ``apply_mjc_actuator_gains`` + config.override_gain_type = "fixed" + config.override_bias_type = "affine" + config.override_gain_prm = [kp, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + config.override_bias_prm = [0.0, -kp, -kd, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] + config.force_usd_conversion = True + config.usd_dir = output_dir + mjcf_converter = MjcfConverter(config) + + from pxr import Usd + + stage = Usd.Stage.Open(mjcf_converter.usd_path) + actuator_prims = [p for p in stage.Traverse() if p.GetTypeName() == "MjcActuator"] + assert len(actuator_prims) > 0, "Expected MjcActuator prims in nv_ant.xml output" + + for prim in actuator_prims: + gain_type_attr = prim.GetAttribute("mjc:gainType") + bias_type_attr = prim.GetAttribute("mjc:biasType") + gain_prm_attr = prim.GetAttribute("mjc:gainPrm") + bias_prm_attr = prim.GetAttribute("mjc:biasPrm") + + assert gain_type_attr and gain_type_attr.HasValue() + assert bias_type_attr and bias_type_attr.HasValue() + assert gain_prm_attr and gain_prm_attr.HasValue() + assert bias_prm_attr and bias_prm_attr.HasValue() + + assert gain_type_attr.Get() == "fixed" + assert bias_type_attr.Get() == "affine" + assert abs(gain_prm_attr.Get()[0] - kp) < 1e-6 + assert abs(bias_prm_attr.Get()[1] - (-kp)) < 1e-6 + assert abs(bias_prm_attr.Get()[2] - (-kd)) < 1e-6 diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 9f29a1a446b9..9171243313b3 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -665,8 +665,8 @@ def test_link_density(sim_config): @pytest.mark.isaacsim_ci -def test_collider_type_convex_decomposition(sim_config): - """Verify that collider_type='convex_decomposition' runs without error and produces valid output. +def test_collision_type_convex_decomposition(sim_config): + """Verify that ``collision_type='Convex Decomposition'`` runs without error and produces valid output. Note: MeshCollisionAPI is applied on the intermediate stage before the asset transformer. The transformer may not preserve these schemas in the final output, so this test @@ -678,7 +678,7 @@ def test_collider_type_convex_decomposition(sim_config): os.makedirs(output_dir, exist_ok=True) config.collision_from_visuals = True - config.collider_type = "convex_decomposition" + config.collision_type = "Convex Decomposition" config.force_usd_conversion = True config.usd_dir = output_dir urdf_converter = UrdfConverter(config) From bcd7f8420ac379ac5ab96c17dff16531d06b1441 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Mon, 11 May 2026 15:28:04 -0700 Subject: [PATCH 03/10] improve doc string --- .../isaaclab/sim/converters/mjcf_converter.py | 4 -- .../sim/converters/mjcf_converter_cfg.py | 45 ++++++++++--------- .../isaaclab/sim/converters/urdf_converter.py | 8 ---- .../sim/converters/urdf_converter_cfg.py | 21 ++++++--- 4 files changed, 39 insertions(+), 39 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py index ca3d5dd18e21..3ee234a6fd71 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py @@ -54,10 +54,6 @@ def __init__(self, cfg: MjcfConverterCfg): 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): """Run the Isaac Sim MJCF importer pipeline. diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py index 18fa7ac53800..d08cdf493906 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter_cfg.py @@ -26,10 +26,6 @@ class MjcfConverterCfg(AssetConverterBaseCfg): setting from the base class is not supported by the new MJCF importer and is ignored. """ - # --------------------------------------------------------------- - # Geometry / mesh options - # --------------------------------------------------------------- - merge_mesh: bool = False """Merge meshes where possible to optimize the model. Defaults to False.""" @@ -46,10 +42,6 @@ class MjcfConverterCfg(AssetConverterBaseCfg): self_collision: bool = False """Activate self-collisions between links of the articulation. Defaults to False.""" - # --------------------------------------------------------------- - # Physics / articulation options - # --------------------------------------------------------------- - import_physics_scene: bool = False """Import the physics scene (time step per second, gravity, etc.) from the MJCF file. Defaults to False.""" @@ -71,13 +63,11 @@ class MjcfConverterCfg(AssetConverterBaseCfg): robot_type: str = "Default" """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 to :class:`~isaacsim.asset.importer.mjcf.MJCFImporterConfig`. """ - # --------------------------------------------------------------- - # Actuator gain overrides - # --------------------------------------------------------------- - override_gain_type: str | None = None """MuJoCo actuator gain type override (e.g. ``"fixed"``). Defaults to ``None``. @@ -93,32 +83,43 @@ class MjcfConverterCfg(AssetConverterBaseCfg): """ override_gain_prm: list[float] | None = None - """MuJoCo actuator gain parameter array (10 floats) override. Defaults to ``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 ``None`` leaves 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 = None - """MuJoCo actuator bias parameter array (10 floats) override. Defaults to ``None``. + """MuJoCo actuator bias parameter array override. Defaults to ``None``. ``None`` leaves the value parsed from the MJCF file unchanged. Example for position control: ``[0, -kp, -kd, 0, 0, 0, 0, 0, 0, 0]``. """ - # --------------------------------------------------------------- - # Importer pipeline options - # --------------------------------------------------------------- - run_asset_transformer: bool = True - """Whether to run the asset transformer profile after conversion. Defaults to True. + """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) + - When enabled, the importer restructures the intermediate USD into a layered, - payload-based package. Disable for a single flat USD output. """ run_multi_physics_conversion: bool = True - """Whether to run the MJCF-to-PhysX physics conversion pass. Defaults to True.""" + """Enable to convert compatible MuJoCo attributes to PhysX attributes, such as actuator gains. Defaults to True.""" debug_mode: bool = False """Enable debug mode in the underlying MJCF importer. Defaults to False. diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py index 4f72363b8a17..ff9c132671ec 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py @@ -68,10 +68,6 @@ def __init__(self, cfg: UrdfConverterCfg): super().__init__(cfg=cfg) - """ - Implementation specific methods. - """ - def _convert_asset(self, cfg: UrdfConverterCfg): """Run the Isaac Sim URDF importer pipeline. @@ -115,10 +111,6 @@ def _convert_asset(self, cfg: UrdfConverterCfg): URDFImporter(import_config).import_urdf() - """ - Helper methods. - """ - @staticmethod def _warn_unsupported_features(cfg: UrdfConverterCfg): """Log warnings for configuration options no longer supported by the URDF importer 3.0. diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py index e06785dc4bb0..d1ed21b75215 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter_cfg.py @@ -182,18 +182,29 @@ class NaturalFrequencyGainsCfg: robot_type: str = "Default" """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 to :class:`~isaacsim.asset.importer.urdf.URDFImporterConfig`. """ run_asset_transformer: bool = True - """Whether to run the asset transformer profile after conversion. Defaults to True. - - When enabled, the importer restructures the intermediate USD into a layered, - payload-based package. Disable for a single flat USD output. + """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) """ run_multi_physics_conversion: bool = True - """Whether to run the URDF-to-PhysX joint attribute conversion pass. Defaults to True.""" + """Enable to generate compatible MuJoCo attributes from the URDF joint attributes alongside PhysX. + Defaults to True. + """ debug_mode: bool = False """Enable debug mode in the underlying URDF importer. Defaults to False. From e798f458ebd71e1484d7a47fbb7dd880a4e6368e Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Mon, 11 May 2026 15:37:28 -0700 Subject: [PATCH 04/10] update change log --- .../isaaclab/sim/converters/urdf_utils.py | 19 ------------------- .../isaaclab/test/sim/test_urdf_converter.py | 3 ++- 2 files changed, 2 insertions(+), 20 deletions(-) delete mode 100644 source/isaaclab/isaaclab/sim/converters/urdf_utils.py diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_utils.py b/source/isaaclab/isaaclab/sim/converters/urdf_utils.py deleted file mode 100644 index 2541212eae0c..000000000000 --- a/source/isaaclab/isaaclab/sim/converters/urdf_utils.py +++ /dev/null @@ -1,19 +0,0 @@ -# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -"""Backwards-compatible re-exports for URDF pre-processing utilities. - -Historically, IsaacLab shipped its own copy of ``merge_fixed_joints`` for the URDF -pipeline. That logic has moved to the Isaac Sim URDF importer at -:mod:`isaacsim.asset.importer.urdf.impl.urdf_utils`, so this module now simply re-exports -the canonical implementation to preserve the public import path -``isaaclab.sim.converters.urdf_utils``. -""" - -from __future__ import annotations - -from isaacsim.asset.importer.urdf.impl.urdf_utils import merge_fixed_joints - -__all__ = ["merge_fixed_joints"] diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 9171243313b3..3b5020268a35 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -21,11 +21,12 @@ import pytest import omni.kit.app +from isaacsim.asset.importer.urdf.impl.urdf_utils import merge_fixed_joints +from isaacsim.core.prims import Articulation import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg -from isaaclab.sim.converters.urdf_utils import merge_fixed_joints # Create a fixture for setup and teardown From 5a92366b5f572ec16f5524f3546b13e5c515b515 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Mon, 11 May 2026 17:41:22 -0700 Subject: [PATCH 05/10] remove redundant import --- source/isaaclab/test/sim/test_urdf_converter.py | 1 - 1 file changed, 1 deletion(-) diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 3b5020268a35..040c8bf013ae 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -22,7 +22,6 @@ import omni.kit.app from isaacsim.asset.importer.urdf.impl.urdf_utils import merge_fixed_joints -from isaacsim.core.prims import Articulation import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext From 80b99b4cb20b5fdd6d2320df88ddb1521fe9b112 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Tue, 12 May 2026 12:05:19 -0700 Subject: [PATCH 06/10] fix urdf mjcf unit test failure --- source/isaaclab/test/sim/test_mjcf_converter.py | 3 +++ source/isaaclab/test/sim/test_urdf_converter.py | 3 ++- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 548f68af8244..b5a0e71cc3e0 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -280,6 +280,9 @@ def test_override_actuator_gains(test_setup_teardown): from pxr import Usd stage = Usd.Stage.Open(mjcf_converter.usd_path) + + ant = stage.GetPrimAtPath("/ant") + ant.GetVariantSet("Physics").SetVariantSelection("mujoco") actuator_prims = [p for p in stage.Traverse() if p.GetTypeName() == "MjcActuator"] assert len(actuator_prims) > 0, "Expected MjcActuator prims in nv_ant.xml output" diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 040c8bf013ae..d0a5a3d99183 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -21,7 +21,6 @@ import pytest import omni.kit.app -from isaacsim.asset.importer.urdf.impl.urdf_utils import merge_fixed_joints import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -185,6 +184,8 @@ def test_merge_fixed_joints_xml(): extension_id = manager.get_enabled_extension_id("isaacsim.asset.importer.urdf") extension_path = manager.get_extension_path(extension_id) + from isaacsim.asset.importer.urdf.impl.urdf_utils import merge_fixed_joints + urdf_path = os.path.join(extension_path, "data", "urdf", "tests", "test_merge_joints.urdf") with tempfile.TemporaryDirectory(prefix="isaaclab_test_merge_") as tmpdir: From 41e767c80fb892b8f79e2891cb0d22b8c118644c Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Wed, 13 May 2026 09:42:58 -0700 Subject: [PATCH 07/10] update converter and unit tests --- .../isaaclab/sim/converters/mjcf_converter.py | 5 ++- .../isaaclab/sim/converters/urdf_converter.py | 5 ++- .../isaaclab/test/sim/test_mjcf_converter.py | 35 ++++++++++----- .../isaaclab/test/sim/test_urdf_converter.py | 45 +++++++++++++------ 4 files changed, 64 insertions(+), 26 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py index 3ee234a6fd71..7a9eb5e5026e 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py @@ -90,4 +90,7 @@ def _convert_asset(self, cfg: MjcfConverterCfg): debug_mode=cfg.debug_mode, ) - MJCFImporter(import_config).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) diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py index ff9c132671ec..f30cb50c69a9 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py @@ -109,7 +109,10 @@ def _convert_asset(self, cfg: UrdfConverterCfg): debug_mode=cfg.debug_mode, ) - URDFImporter(import_config).import_urdf() + generated_usd_path = URDFImporter(import_config).import_urdf() + 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) @staticmethod def _warn_unsupported_features(cfg: UrdfConverterCfg): diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index b5a0e71cc3e0..881e8c4bf19a 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -102,7 +102,12 @@ def test_create_prim_from_usd(test_setup_teardown): @pytest.mark.isaacsim_ci def test_self_collision(test_setup_teardown): - """Verify that ``self_collision=True`` enables self-collisions on the articulation.""" + """Verify that ``self_collision=True`` enables self-collisions on the Newton articulation root. + + The Isaac Sim importer's ``enable_self_collision`` writes the ``newton:selfCollisionEnabled`` + attribute on prims tagged as articulation roots (``UsdPhysics.ArticulationRootAPI``, + ``PhysicsArticulationRootAPI``, or ``NewtonArticulationRootAPI``). + """ sim, config = test_setup_teardown test_dir = os.path.dirname(os.path.abspath(__file__)) output_dir = os.path.join(test_dir, "output", "mjcf_self_collision") @@ -113,19 +118,27 @@ def test_self_collision(test_setup_teardown): config.usd_dir = output_dir mjcf_converter = MjcfConverter(config) - from pxr import PhysxSchema, Usd + from pxr import Usd, UsdPhysics stage = Usd.Stage.Open(mjcf_converter.usd_path) + + articulation_roots = [ + prim + for prim in stage.Traverse() + if prim.HasAPI(UsdPhysics.ArticulationRootAPI) + or prim.HasAPI("PhysicsArticulationRootAPI") + or prim.HasAPI("NewtonArticulationRootAPI") + ] + assert articulation_roots, "Expected at least one articulation root in the converted USD" + found_self_collision = False - for prim in stage.Traverse(): - if prim.HasAPI(PhysxSchema.PhysxArticulationAPI): - physx_api = PhysxSchema.PhysxArticulationAPI(prim) - sc_attr = physx_api.GetEnabledSelfCollisionsAttr() - if sc_attr and sc_attr.HasValue() and sc_attr.Get(): - found_self_collision = True - break - - assert found_self_collision, "Expected self-collision to be enabled on the articulation" + for prim in articulation_roots: + sc_attr = prim.GetAttribute("newton:selfCollisionEnabled") + if sc_attr and sc_attr.HasValue() and sc_attr.Get(): + found_self_collision = True + break + + assert found_self_collision, "Expected ``newton:selfCollisionEnabled`` to be True on a Newton articulation root" @pytest.mark.isaacsim_ci diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index d0a5a3d99183..7794546a21aa 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -78,7 +78,13 @@ def test_no_change(sim_config): @pytest.mark.isaacsim_ci def test_config_change(sim_config): """Call conversion twice but change the config in the second call. This should generate a new USD file.""" + sim, config = sim_config + test_dir = os.path.dirname(os.path.abspath(__file__)) + output_dir = os.path.join(test_dir, "output", "urdf_config_change") + os.makedirs(output_dir, exist_ok=True) + + config.usd_dir = output_dir urdf_converter = UrdfConverter(config) time_usd_file_created = os.stat(urdf_converter.usd_path).st_mtime_ns @@ -86,7 +92,7 @@ def test_config_change(sim_config): new_config = config new_config.fix_base = not config.fix_base # define the usd directory - new_config.usd_dir = urdf_converter.usd_dir + new_config.usd_dir = output_dir # convert to usd but this time in the same directory as previous step new_urdf_converter = UrdfConverter(new_config) new_time_usd_file_created = os.stat(new_urdf_converter.usd_path).st_mtime_ns @@ -360,7 +366,12 @@ def test_no_collision_from_visuals(sim_config): @pytest.mark.isaacsim_ci def test_self_collision(sim_config): - """Verify that self_collision=True enables self-collision on the articulation.""" + """Verify that ``self_collision=True`` enables self-collision on the Newton articulation root. + + The Isaac Sim importer's ``enable_self_collision`` writes the ``newton:selfCollisionEnabled`` + attribute on prims tagged as articulation roots (``UsdPhysics.ArticulationRootAPI``, + ``PhysicsArticulationRootAPI``, or ``NewtonArticulationRootAPI``). + """ sim, config = sim_config test_dir = os.path.dirname(os.path.abspath(__file__)) output_dir = os.path.join(test_dir, "output", "urdf_self_collision") @@ -371,21 +382,29 @@ def test_self_collision(sim_config): config.usd_dir = output_dir urdf_converter = UrdfConverter(config) - from pxr import PhysxSchema, Usd + from pxr import Usd, UsdPhysics stage = Usd.Stage.Open(urdf_converter.usd_path) - # find prim with PhysxArticulationAPI and check self-collision flag + articulation_roots = [ + prim + for prim in stage.Traverse() + if prim.HasAPI(UsdPhysics.ArticulationRootAPI) + or prim.HasAPI("PhysicsArticulationRootAPI") + or prim.HasAPI("NewtonArticulationRootAPI") + ] + assert articulation_roots, "Expected at least one articulation root in the converted USD" + found_self_collision = False - for prim in stage.Traverse(): - if prim.HasAPI(PhysxSchema.PhysxArticulationAPI): - physx_api = PhysxSchema.PhysxArticulationAPI(prim) - sc_attr = physx_api.GetEnabledSelfCollisionsAttr() - if sc_attr and sc_attr.HasValue() and sc_attr.Get(): - found_self_collision = True - break - - assert found_self_collision, "Expected self-collision to be enabled on the articulation" + for prim in articulation_roots: + print(prim.GetName()) + print(prim.GetAttribute("newton:selfCollisionEnabled")) + sc_attr = prim.GetAttribute("newton:selfCollisionEnabled") + if sc_attr and sc_attr.HasValue() and sc_attr.Get(): + found_self_collision = True + break + + assert found_self_collision, "Expected ``newton:selfCollisionEnabled`` to be True on a Newton articulation root" @pytest.mark.isaacsim_ci From a3a3d0a4246fa265d818dc9d65173059265caec2 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Wed, 13 May 2026 10:11:12 -0700 Subject: [PATCH 08/10] update doc, and mjcf converter output logic --- docs/source/how-to/import_new_asset.rst | 117 ++++++++++++++++-- .../isaaclab/sim/converters/mjcf_converter.py | 9 -- 2 files changed, 110 insertions(+), 16 deletions(-) diff --git a/docs/source/how-to/import_new_asset.rst b/docs/source/how-to/import_new_asset.rst index e241be44e96e..e6af60abd93e 100644 --- a/docs/source/how-to/import_new_asset.rst +++ b/docs/source/how-to/import_new_asset.rst @@ -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. @@ -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 ```` 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 + ```` 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 @@ -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. @@ -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 + ```` 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 ~~~~~~~~~~~~~ @@ -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% diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py index 7a9eb5e5026e..226bcf3a5a31 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py @@ -6,7 +6,6 @@ from __future__ import annotations import os -import shutil from .asset_converter_base import AssetConverterBase from .mjcf_converter_cfg import MjcfConverterCfg @@ -62,14 +61,6 @@ def _convert_asset(self, cfg: MjcfConverterCfg): """ from isaacsim.asset.importer.mjcf import MJCFImporter, MJCFImporterConfig - # Clean up any existing output subdirectory so the importer writes fresh files. - # 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, From f1addb0f49fdd4832a5317030bf9bcc45fa2f292 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Thu, 14 May 2026 09:47:04 -0700 Subject: [PATCH 09/10] fix changlog --- .../stevfeng-fix-converter-usd-path.minor.rst | 39 +++++++++++++++++ source/isaaclab/docs/CHANGELOG.rst | 43 ------------------- 2 files changed, 39 insertions(+), 43 deletions(-) create mode 100644 source/isaaclab/changelog.d/stevfeng-fix-converter-usd-path.minor.rst diff --git a/source/isaaclab/changelog.d/stevfeng-fix-converter-usd-path.minor.rst b/source/isaaclab/changelog.d/stevfeng-fix-converter-usd-path.minor.rst new file mode 100644 index 000000000000..148af70ffc84 --- /dev/null +++ b/source/isaaclab/changelog.d/stevfeng-fix-converter-usd-path.minor.rst @@ -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. diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index cd0d117281bb..6c524bc8d2d1 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,49 +1,6 @@ Changelog --------- -5.3.0 (2026-05-14) -~~~~~~~~~~~~~~~~~~~ - -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. - 5.2.0 (2026-05-14) ~~~~~~~~~~~~~~~~~~ From d7d45bae98999e766b1443b1bf71bdb9fc1ef3a3 Mon Sep 17 00:00:00 2001 From: Steven Feng Date: Thu, 14 May 2026 10:30:57 -0700 Subject: [PATCH 10/10] fix docs --- docs/source/how-to/import_new_asset.rst | 16 ++++++++-------- source/isaaclab/docs/CHANGELOG.rst | 3 +++ 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/docs/source/how-to/import_new_asset.rst b/docs/source/how-to/import_new_asset.rst index e6af60abd93e..938d0720eb9e 100644 --- a/docs/source/how-to/import_new_asset.rst +++ b/docs/source/how-to/import_new_asset.rst @@ -47,7 +47,7 @@ The URDF importer has various configuration parameters that can be set to contro 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 @@ -72,7 +72,7 @@ Articulation and joint structure ``PDGainsCfg`` instead. Geometry, collisions, and materials -""""""""""""""""""""""""""""""""""" +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ * :attr:`~sim.converters.UrdfConverterCfg.collision_from_visuals` - Whether to create collision geometry from visual geometry when no explicit ```` is defined for a link. Defaults to ``False``. @@ -86,7 +86,7 @@ Geometry, collisions, and materials ```` 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``. @@ -101,7 +101,7 @@ Asset resolution and output 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. @@ -225,7 +225,7 @@ parameters, please check the the documentation at `MJCF importer`_. 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``. @@ -238,7 +238,7 @@ Geometry, collisions, and materials 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``. @@ -249,7 +249,7 @@ Articulation and physics ``--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``, @@ -265,7 +265,7 @@ which leaves the parsed values unchanged. 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"``, diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 6c524bc8d2d1..8cc881bae674 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -119,6 +119,7 @@ Fixed installable alongside ``isaacsim==6.0.0.0``. Users who want the Viser visualizer can request it explicitly with ``isaaclab[viser]``. + 5.1.1 (2026-05-13) ~~~~~~~~~~~~~~~~~~ @@ -141,6 +142,7 @@ Fixed when Fabric is unavailable, with no impact on the cloning speedup when Fabric is present. + 5.1.0 (2026-05-12) ~~~~~~~~~~~~~~~~~~ @@ -190,6 +192,7 @@ Fixed * Fixed extension installation to honor ``pip_upgrade_dependencies`` declared in ``config/extension.toml``. + 5.0.0 (2026-05-11) ~~~~~~~~~~~~~~~~~~