From 92f84278eb1ac817a0a6681805f4f419e8469d57 Mon Sep 17 00:00:00 2001 From: Piotr Barejko Date: Fri, 5 Jun 2026 14:02:57 -0700 Subject: [PATCH 01/40] Update rendering documentation and import guard with documentation how to install ovrtx (#5991) # Description Documentation was out of date. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../overview/core-concepts/renderers.rst | 37 ++++++++++++------- .../pbarejko-ovrtx-updated-documentation.rst | 6 +++ .../isaaclab_ov/renderers/ovrtx_renderer.py | 12 +++++- 3 files changed, 41 insertions(+), 14 deletions(-) create mode 100644 source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst diff --git a/docs/source/overview/core-concepts/renderers.rst b/docs/source/overview/core-concepts/renderers.rst index 458901824139..d2ff6a4ca922 100644 --- a/docs/source/overview/core-concepts/renderers.rst +++ b/docs/source/overview/core-concepts/renderers.rst @@ -7,11 +7,13 @@ Isaac Lab uses a pluggable renderer architecture to support different rendering The :class:`~isaaclab.renderers.BaseRenderer` abstract base class defines the interface that all renderer implementations must follow. -Isaac Lab supports two rendering backends: +Isaac Lab supports three rendering backends: -- **RTX renderer** (``IsaacRtxRendererCfg`` / ``OVRTXRendererCfg``) — NVIDIA's Omniverse RTX - rendering pipeline. Requires Isaac Sim. Best for photorealistic rendering, full camera sensor - support (RGB, depth, semantic segmentation, etc.), and production quality outputs. +- **Isaac RTX renderer** (``IsaacRtxRendererCfg``) — NVIDIA's Omniverse RTX rendering pipeline + running inside Isaac Sim. Requires Isaac Sim. Best for photorealistic rendering, full camera + sensor support (RGB, depth, semantic segmentation, etc.), and production quality outputs. +- **OVRTX renderer** (``OVRTXRendererCfg``) — A standalone RTX path-tracing renderer provided by + the ``isaaclab_ov`` extension. Delivers RTX-quality rendering. - **Newton Warp renderer** (``NewtonWarpRendererCfg``) — A lightweight GPU-accelerated renderer built on NVIDIA Warp. Works with the Newton physics backend and does **not** require Isaac Sim (kit-less mode). Ideal for training workflows where full RTX fidelity is not needed. @@ -25,7 +27,8 @@ Choosing a renderer backend | Isaac RTX | Yes | Full sensor fidelity, RTX | | | | photorealism, PhysX backend | +---------------------+-------------------------------+---------------------------------+ -| OVRTX | Yes (+ ``isaaclab_ov``) | Alternative RTX pipeline | +| OVRTX | No (kit-less; needs | RTX-quality rendering without | +| | ``isaaclab_ov`` + ``ovrtx``) | requiring Isaac Sim | +---------------------+-------------------------------+---------------------------------+ | Newton Warp | No (kit-less) | Newton backend, fast training | +---------------------+-------------------------------+---------------------------------+ @@ -111,22 +114,30 @@ Core concepts Installing the OVRTX renderer ------------------------------ -The OVRTX renderer is provided by the ``isaaclab_ov`` extension and requires the -`ovrtx `_ package (hosted on -``pypi.nvidia.com``). +The OVRTX renderer is provided by the ``isaaclab_ov`` extension. The extension's +source package ships with the core install, but the renderer's ``ovrtx`` runtime +wheel (the `ovrtx `_ package, hosted on +``pypi.nvidia.com``) is **not** installed by default. You must request it +explicitly — OVRTX does **not** require Isaac Sim. -Install via the Isaac Lab CLI: +Install via the Isaac Lab CLI using the ``ov[ovrtx]`` token: .. code-block:: bash - # Install isaaclab_ov (and its ovrtx dependency) alongside the core package - ./isaaclab.sh -i ov + # Install the ovrtx runtime wheel on top of an existing install + ./isaaclab.sh -i ov[ovrtx] -Or install manually with pip: +.. note:: + + The bare ``ov`` token does **not** install any runtime wheel (the source + packages are already part of the core install). Use ``ov[ovrtx]`` (or ``ov[all]``) + to pull in the ``ovrtx`` dependency. + +Or install manually with pip (note the ``[ovrtx]`` extra and the extra index URL): .. code-block:: bash - pip install --extra-index-url https://pypi.nvidia.com -e source/isaaclab_ov + pip install --extra-index-url https://pypi.nvidia.com -e "source/isaaclab_ov[ovrtx]" - **Opaque render data**: The render data object returned by :meth:`~isaaclab.renderers.BaseRenderer.create_render_data` is passed to subsequent renderer methods. It should be completely opaque to the caller: inspecting or modifying it diff --git a/source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst b/source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst new file mode 100644 index 000000000000..47564d50edb4 --- /dev/null +++ b/source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed the OVRTX renderer to raise a clear, actionable error when the optional + ``ovrtx`` runtime wheel is not installed, pointing users to + ``./isaaclab.sh -i 'ov[ovrtx]'`` instead of a cryptic ``No module named 'ovrtx'``. diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index 9d31953a5213..bd724fdda4fc 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -39,7 +39,17 @@ # By setting OVRTX_SKIP_USD_CHECK, we prevent the C library from loading the pxr Python package. os.environ["OVRTX_SKIP_USD_CHECK"] = "1" -from ovrtx import Device, PrimMode, Renderer, RendererConfig, Semantic + +try: + from ovrtx import Device, PrimMode, Renderer, RendererConfig, Semantic +except ModuleNotFoundError as exc: + if exc.name != "ovrtx": + raise + raise ModuleNotFoundError( + "The OVRTX renderer requires the optional 'ovrtx' runtime wheel, which is not installed. " + "Install it with: ./isaaclab.sh -i 'ov[ovrtx]' " + "(or, manually: pip install --extra-index-url https://pypi.nvidia.com -e 'source/isaaclab_ov[ovrtx]')." + ) from exc from isaaclab.renderers import BaseRenderer, RenderBufferKind, RenderBufferSpec from isaaclab.sim import SimulationContext From 7aac4c69568815874bf4c9816d2b65d193ccb09f Mon Sep 17 00:00:00 2001 From: hujc Date: Fri, 5 Jun 2026 15:38:31 -0700 Subject: [PATCH 02/40] [Fix] Make create_cube_base_env tutorial run with USD-level randomization (#5996) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## 1. Summary * The ``create_cube_base_env`` tutorial crashed at startup with ``RuntimeError: Scene replication is enabled ...`` from the event manager: the scene was constructed with ``replicate_physics=True`` while declaring two ``prestartup`` USD-level randomization terms (``randomize_scale``, ``randomize_color``). * One-line fix: ``replicate_physics=True`` → ``False`` on the scene cfg — matching the tutorial's docstring and the comment directly above the line, both of which already state it should be ``False``. * Regression from #4649 (cloner refactor), which flipped this line without updating the comment or accounting for the prestartup guard. ## 2. Verification (Isaac Sim 6.0.0.1, headless) * Before (``True``): ``RuntimeError`` raised in ``EventManager._prepare_terms``; 0 simulation steps. * After (``False``): both prestartup terms active; the env runs 64,588 steps with the cube-tracking error converging 63.5 → 0.19. ## 3. Test plan * [x] Reproduced the crash on develop as-is * [x] Verified the fix runs the tutorial headless with USD-level randomization active Refs: NVBug 6269154 --- scripts/tutorials/03_envs/create_cube_base_env.py | 2 +- .../jichuanh-fix-cube-base-env-replicate-physics.rst | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) create mode 100644 source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst diff --git a/scripts/tutorials/03_envs/create_cube_base_env.py b/scripts/tutorials/03_envs/create_cube_base_env.py index f1deeabc927e..a2b4224acd14 100644 --- a/scripts/tutorials/03_envs/create_cube_base_env.py +++ b/scripts/tutorials/03_envs/create_cube_base_env.py @@ -288,7 +288,7 @@ class CubeEnvCfg(ManagerBasedEnvCfg): # The flag 'replicate_physics' is set to False, which means that the cube is not replicated # across multiple environments but rather each environment gets its own cube instance. # This allows modifying the cube's properties independently for each environment. - scene: MySceneCfg = MySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.5, replicate_physics=True) + scene: MySceneCfg = MySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.5, replicate_physics=False) # Basic settings observations: ObservationsCfg = ObservationsCfg() diff --git a/source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst b/source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst new file mode 100644 index 000000000000..c98b503c6eca --- /dev/null +++ b/source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed the ``create_cube_base_env`` tutorial crashing at startup with a ``RuntimeError`` + because its prestartup USD-level randomization terms ran while scene replication was enabled. From 28b1e897bddb3b299ea4988d43a7590e11fa5d3a Mon Sep 17 00:00:00 2001 From: matthewtrepte Date: Fri, 5 Jun 2026 17:36:46 -0700 Subject: [PATCH 03/40] General Visualizer Fixes (#5935) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Fixes - remove legacy isaaclab_visualizers/setup.py - fix too small ground plane mesh in Rerun and Viser visualizers in some envs - fix flickering ground in Viser visualizer - fix library conflict with imgui_bundle, which broke Newton viewer's HUD - expand viz test to include a specific check for imgui_bundle failure to load (this often occurs due to new conflict libraries which causes Newton visualizer HUD to break) - prevent log spam from [Warning] [omni.physx.tensors.plugin] Failed to find rigid body... - add contact arrows to newton visualizer with a limitation note to the visualization docs - fix an edgecase where wrong viz marker prototype is used when marker count equals number of prototype - move the xr visualization test from test/visualization -> test/xr_visualization to separate it more from test/visualizers ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/index.rst | 1 - .../source/how-to/optimize_stage_creation.rst | 2 +- .../overview/core-concepts/visualization.rst | 20 +- docs/source/refs/migration.rst | 4 +- .../clarify-single-video-stream.rst | 6 + .../clarify-visualizer-camera-sensor-mode.rst | 6 + ...fix-scene-data-articulation-transforms.rst | 6 + .../isaaclab/isaaclab/cli/commands/install.py | 2 +- .../isaaclab/envs/utils/camera_view.py | 15 +- .../isaaclab/envs/utils/video_recorder.py | 8 + .../isaaclab/markers/visualization_markers.py | 8 +- .../scene_data/scene_data_provider.py | 12 ++ .../isaaclab/test/envs/test_video_recorder.py | 11 ++ .../markers/test_visualization_markers.py | 28 +++ .../check_scene_xr_visualization.py | 2 +- .../expose-newton-contact-buffer.rst | 5 + .../isaaclab_newton/physics/newton_manager.py | 5 + .../reduce-ant-joint-wrench-warnings.rst | 6 + .../isaaclab_physx/physics/physx_manager.py | 29 ++- .../fix-newton-contact-visualization.rst | 6 + .../fix-newton-hud-imgui-dependency.rst | 15 ++ .../newton/newton_visualizer.py | 124 ++++++++++++ .../isaaclab_visualizers/newton_adapter.py | 46 +++++ .../rerun/rerun_visualizer.py | 30 ++- .../viser/viser_visualizer.py | 81 +++++++- source/isaaclab_visualizers/pyproject.toml | 5 + .../test/test_newton_adapter.py | 180 +++++++++++++++++- .../test_visualizer_integration_newton.py | 5 +- .../test/test_visualizer_integration_physx.py | 5 +- ...est_visualizer_tiled_integration_newton.py | 5 +- ...test_visualizer_tiled_integration_physx.py | 5 +- .../test/visualizer_integration_utils.py | 14 ++ tools/wheel_builder/res/python_packages.toml | 2 +- 33 files changed, 671 insertions(+), 28 deletions(-) create mode 100644 source/isaaclab/changelog.d/clarify-single-video-stream.rst create mode 100644 source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst create mode 100644 source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst rename source/isaaclab/test/{visualization => xr_visualization}/check_scene_xr_visualization.py (98%) create mode 100644 source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst create mode 100644 source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst create mode 100644 source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst create mode 100644 source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst diff --git a/docs/index.rst b/docs/index.rst index 448d897852e0..2a304b8f8d7b 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -130,7 +130,6 @@ Table of Contents source/features/hydra source/features/multi_gpu source/features/population_based_training - Tiled Rendering source/features/ray source/features/reproducibility diff --git a/docs/source/how-to/optimize_stage_creation.rst b/docs/source/how-to/optimize_stage_creation.rst index 293ee84ec7d3..3b6a6b28924a 100644 --- a/docs/source/how-to/optimize_stage_creation.rst +++ b/docs/source/how-to/optimize_stage_creation.rst @@ -49,7 +49,7 @@ Stage in memory can be toggled by setting the :attr:`isaaclab.sim.SimulationCfg. env = ManagerBasedRLEnv(cfg=cfg) When using stage in memory without an existing RL environment class, wrap the stage creation steps -in a :py:keyword:`with` statement to set the stage context. The stage is automatically attached +in a ``with`` statement to set the stage context. The stage is automatically attached to the USD context when ``SimulationContext`` is created with ``create_stage_in_memory=True``. **Using Stage in Memory with a manual scene setup** diff --git a/docs/source/overview/core-concepts/visualization.rst b/docs/source/overview/core-concepts/visualization.rst index 8fa20c86a652..f25042e7437b 100644 --- a/docs/source/overview/core-concepts/visualization.rst +++ b/docs/source/overview/core-concepts/visualization.rst @@ -222,11 +222,16 @@ Note, Kit tiled camera views require launching with ``--enable_cameras``. - ``tiled_cam_view=False``, ``eye=(4, -4, 3)``, ``lookat=(0, 0, 0)`` - Interactive visualizer camera starts at ``eye`` and looks at the fixed ``lookat`` coordinate. * - Generated tiled camera - - ``tiled_cam_view=True``, ``tiled_cam_prim_path=None``, ``tiled_cam_target_prim_path="/World/envs/*/Robot/base"`` + - ``tiled_cam_view=True``, ``tiled_cam_prim_path=None``, ``tiled_cam_target_prim_path="/World/envs/*/Robot"`` - The visualizer creates per-env cameras. Each camera looks at the matched target prim, with ``tiled_cam_eye`` as an offset from that target. + Note that the ``tiled_cam_target_prim_path`` has a default value, but different environments may require different paths. * - Existing tiled camera sensors - ``tiled_cam_view=True``, ``tiled_cam_prim_path="/World/envs/*/Camera"`` - - The visualizer displays existing Isaac Lab ``Camera`` sensor output. Generated-camera fields such as ``tiled_cam_eye`` and ``tiled_cam_target_prim_path`` are ignored. + - The visualizer displays existing Isaac Lab ``Camera`` sensor output. Generated-camera fields such as ``tiled_cam_eye`` and + ``tiled_cam_target_prim_path`` are ignored. Note that the ``tiled_cam_prim_path`` has a default value, but different + environments may require different paths. This mode requires an environment that registers Isaac Lab ``Camera`` sensors + in ``scene.sensors``. For Cartpole, use a camera task such as ``Isaac-Cartpole-Camera``. The plain ``Isaac-Cartpole`` + task has no ``/World/envs/*/Camera`` sensor, so leave ``tiled_cam_prim_path=None`` to use generated visualizer cameras. **How to Access the Tiled Camera View in the UI** @@ -419,8 +424,8 @@ Newton Visualizer tiled_cam_prim_path=None, # Existing Camera sensor prim path, e.g. "/World/envs/*/Camera" tiled_cam_eye=(4.0, -4.0, 3.0), # Eye offset for generated tiled cameras tiled_cam_target_prim_path=( # Prim that generated cameras follow/look at - "/World/envs/*/Robot/base" - ), + "/World/envs/*/Robot" # This is the default value, but different environments + ), # may require a different paths. # Performance tuning update_frequency=1, # Update every N frames (1=every frame) @@ -606,6 +611,13 @@ The FPS control in the Rerun visualizer UI may not affect the visualization fram Currently, live plots are only available in the Kit Visualizer. +**Newton Contact Visualization** + +Newton's native ``Show Contacts`` view can show all contacts from the Newton physics contact buffer. When running +with PhysX, the Newton visualizer can only show contacts reported by configured Isaac Lab contact sensors, so +currently the set of displayed contacts may differ across backends. + + **Viser Visualizer Renderer Requirement** The Viser visualizer requires a Newton model, which is provided automatically by diff --git a/docs/source/refs/migration.rst b/docs/source/refs/migration.rst index 3ae599e91509..11db227bc142 100644 --- a/docs/source/refs/migration.rst +++ b/docs/source/refs/migration.rst @@ -157,7 +157,7 @@ Two key patterns support this: initialized. For full details, examples, and the ``{DIR}`` placeholder convention, see the -:ref:`contributing` guide — in particular the +:doc:`contributing` guide — in particular the `Lazy Loading & Module Exports `__, `Resolvable Strings `__, and `Config + Implementation File Split `__ @@ -197,7 +197,7 @@ With this in place, ``import my_package`` will not eagerly import any submodules are loaded on first access, giving ``SimulationApp`` time to initialize and auto-detect the correct backend. -For more details, refer to the :ref:`contributing` guide. +For more details, refer to the :doc:`contributing` guide. .. _simple script: https://gist.github.com/kellyguo11/3e8f73f739b1c013b1069ad372277a85 diff --git a/source/isaaclab/changelog.d/clarify-single-video-stream.rst b/source/isaaclab/changelog.d/clarify-single-video-stream.rst new file mode 100644 index 000000000000..39e5bacdc191 --- /dev/null +++ b/source/isaaclab/changelog.d/clarify-single-video-stream.rst @@ -0,0 +1,6 @@ +Changed +^^^^^^^ + +* Clarified ``--video`` behavior when multiple video-capable visualizers are active: + Gymnasium video recording captures one ``env.render()`` stream, with Kit taking + priority over Newton. diff --git a/source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst b/source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst new file mode 100644 index 000000000000..cb6f9c0081f7 --- /dev/null +++ b/source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Improved visualizer tiled-camera errors when ``tiled_cam_prim_path`` is set but + the scene has no Isaac Lab ``Camera`` sensors, and clarified the camera-mode + documentation for Cartpole camera tasks. diff --git a/source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst b/source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst new file mode 100644 index 000000000000..14be85dbc997 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst @@ -0,0 +1,6 @@ +Added +^^^^^ + +* Added a scene-data backend hook for active ``InteractiveScene`` access so + backends can source scene-owned entity transforms without relying on global + rigid-body views, and visualizers can discover scene-owned contact sensors. diff --git a/source/isaaclab/isaaclab/cli/commands/install.py b/source/isaaclab/isaaclab/cli/commands/install.py index 2fe6368b65d0..f4d141dc4a08 100644 --- a/source/isaaclab/isaaclab/cli/commands/install.py +++ b/source/isaaclab/isaaclab/cli/commands/install.py @@ -652,7 +652,7 @@ def _install_extra_feature(feature_name: str, selector: str = "") -> None: elif feature_name == "newton": if selector: print_warning(f"'newton' does not support selectors (got '{selector}'). Installing all newton extras.") - print_info("Installing newton extras (newton[sim], PyOpenGL-accelerate, imgui-bundle)...") + print_info("Installing newton extras (newton[sim], PyOpenGL-accelerate, imgui-bundle, typing-extensions)...") run_command(pip_cmd + ["install", "--editable", f"{source_dir}/isaaclab_newton[all]"]) run_command(pip_cmd + ["install", "--editable", f"{source_dir}/isaaclab_physx[newton]"]) run_command(pip_cmd + ["install", "--editable", f"{source_dir}/isaaclab_visualizers[newton]"]) diff --git a/source/isaaclab/isaaclab/envs/utils/camera_view.py b/source/isaaclab/isaaclab/envs/utils/camera_view.py index 6f5c193d4ecd..a686e0e65b16 100644 --- a/source/isaaclab/isaaclab/envs/utils/camera_view.py +++ b/source/isaaclab/isaaclab/envs/utils/camera_view.py @@ -92,7 +92,20 @@ def find_camera_by_prim_path(camera_sensors: dict[str, Camera], cam_prim_path: s f"cam_prim_path={cam_prim_path!r} matched USD camera prims, but no Isaac Lab Camera sensor owns them. " "Add the camera to scene.sensors or leave tiled_cam_prim_path unset to use generated tiled cameras." ) - raise RuntimeError(f"No Isaac Lab Camera sensor matched cam_prim_path={cam_prim_path!r}.") + if not camera_sensors: + raise RuntimeError( + f"No Isaac Lab Camera sensors are registered in the scene, so tiled_cam_prim_path={cam_prim_path!r} " + "cannot be used. Use an environment that defines Camera sensors, or leave tiled_cam_prim_path unset " + "to use generated tiled cameras." + ) + available_paths = { + getattr(camera.cfg, "prim_path", None) for camera in camera_sensors.values() if getattr(camera, "cfg", None) + } + raise RuntimeError( + f"No Isaac Lab Camera sensor matched cam_prim_path={cam_prim_path!r}. " + f"Available Camera sensor prim paths: {sorted(path for path in available_paths if path)}. " + "Leave tiled_cam_prim_path unset to use generated tiled cameras." + ) def ensure_camera_initialized(camera: Camera) -> None: diff --git a/source/isaaclab/isaaclab/envs/utils/video_recorder.py b/source/isaaclab/isaaclab/envs/utils/video_recorder.py index 3ff6a7e1a0a4..0925b4a0ab1c 100644 --- a/source/isaaclab/isaaclab/envs/utils/video_recorder.py +++ b/source/isaaclab/isaaclab/envs/utils/video_recorder.py @@ -71,6 +71,14 @@ def _resolve_video_backend( # Prefer the visualizer backend when --visualizer is active alongside --video. visualizer_types: list[str] = scene.sim.resolve_visualizer_types() if backend_source == "visualizer" else [] if visualizer_types: + supported_visualizers = [viz for viz in ("kit", "newton") if viz in visualizer_types] + if len(supported_visualizers) > 1: + logger.warning( + "[VideoRecorder] Multiple video-capable visualizers are active (%s), but --video records one " + "env.render() stream. Using Kit because it has priority. Run with only --viz newton to record " + "a Newton GL video.", + supported_visualizers, + ) # kit takes priority when multiple visualizers are active for preferred in ("kit", "newton"): if preferred in visualizer_types: diff --git a/source/isaaclab/isaaclab/markers/visualization_markers.py b/source/isaaclab/isaaclab/markers/visualization_markers.py index 667f9b4ddf7d..ef9eb65e9927 100644 --- a/source/isaaclab/isaaclab/markers/visualization_markers.py +++ b/source/isaaclab/isaaclab/markers/visualization_markers.py @@ -111,6 +111,7 @@ def __init__(self, cfg: VisualizationMarkersCfg): self.prim_path = cfg.prim_path self._count = len(cfg.markers) self._is_visible = True + self._has_visualized = False self._backends: list[object] = [] self._ensure_backends_initialized() @@ -226,7 +227,11 @@ def visualize( if value is not None: num_markers = value.shape[0] - if norm_marker_indices is None and num_markers != 0 and num_markers != self._count: + if ( + norm_marker_indices is None + and num_markers != 0 + and (not self._has_visualized or num_markers != self._count) + ): norm_marker_indices = torch.zeros(num_markers, dtype=torch.int32, device=target_device) elif norm_marker_indices is None and num_markers == 0: if all(value is None for value in (norm_translations, norm_orientations, norm_scales)): @@ -238,6 +243,7 @@ def visualize( if num_markers != 0: self._count = num_markers + self._has_visualized = True def __del__(self): for backend in getattr(self, "_backends", []): diff --git a/source/isaaclab/isaaclab/scene_data/scene_data_provider.py b/source/isaaclab/isaaclab/scene_data/scene_data_provider.py index 9d888347e38e..ba4c051920e1 100644 --- a/source/isaaclab/isaaclab/scene_data/scene_data_provider.py +++ b/source/isaaclab/isaaclab/scene_data/scene_data_provider.py @@ -56,6 +56,18 @@ def get_camera_sensors(self) -> dict[str, Any]: if isinstance(sensor, Camera) } + def get_contact_sensors(self) -> dict[str, Any]: + """Return Isaac Lab contact sensors keyed by scene sensor name.""" + if self._interactive_scene is None: + return {} + from isaaclab.sensors.contact_sensor import BaseContactSensor + + return { + name: sensor + for name, sensor in getattr(self._interactive_scene, "sensors", {}).items() + if isinstance(sensor, BaseContactSensor) + } + @property def transform_count(self) -> int: """Number of transforms available from the sim backend.""" diff --git a/source/isaaclab/test/envs/test_video_recorder.py b/source/isaaclab/test/envs/test_video_recorder.py index 91af56632d6b..e22cbe656147 100644 --- a/source/isaaclab/test/envs/test_video_recorder.py +++ b/source/isaaclab/test/envs/test_video_recorder.py @@ -172,6 +172,17 @@ def test_resolve_backend_kit_wins_over_newton_visualizer(): assert matched == "kit" +def test_resolve_backend_warns_when_multiple_video_capable_visualizers(caplog: pytest.LogCaptureFixture): + """The Gymnasium video wrapper records one stream even if both Kit and Newton are active.""" + scene = _make_scene(["newton", "kit"]) + with caplog.at_level("WARNING"): + backend, matched = _resolve_video_backend(scene) + + assert backend == "kit" + assert matched == "kit" + assert any("Multiple video-capable visualizers are active" in record.getMessage() for record in caplog.records) + + def test_resolve_backend_unsupported_visualizer_falls_through(): """viser/rerun visualizers fall through to physics stack detection.""" scene = _make_scene(["viser"], physics_name="PhysxPhysicsManager") diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index b9ae8387cf0f..79a66443eca1 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -144,6 +144,26 @@ def test_rendering_context_authors_visible_usd_point_instancer(sim): assert list(instancer.GetProtoIndicesAttr().Get()) == [0, 1] +def test_first_visualize_defaults_to_first_prototype_when_count_matches_prototypes(sim): + """Omitted marker indices should not preserve initialization prototype placeholders.""" + from pxr import UsdGeom + + sim._has_offscreen_render = True + config = VisualizationMarkersCfg( + prim_path="/World/Visuals/default_marker_indices", + markers={ + "frame": sim_utils.SphereCfg(radius=0.1), + "line": sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + }, + ) + test_marker = VisualizationMarkers(config) + + test_marker.visualize(translations=torch.tensor([[0.0, 0.0, 0.0], [0.2, 0.0, 0.0]], device=sim.device)) + + instancer = UsdGeom.PointInstancer(sim_utils.get_current_stage().GetPrimAtPath(test_marker.prim_path)) + assert list(instancer.GetProtoIndicesAttr().Get()) == [0, 0] + + def test_usd_marker(sim): """Test with marker from a USD.""" # create a marker @@ -253,6 +273,7 @@ class _FakeViewer: def __init__(self): self.calls = [] + self.show_contacts = False def is_paused(self): return False @@ -263,6 +284,9 @@ def begin_frame(self, sim_time): def log_state(self, state): self.calls.append(("log_state", state)) + def log_arrows(self, name, starts, ends, colors): + pass + def end_frame(self): self.calls.append(("end_frame",)) @@ -276,6 +300,10 @@ def get_state(scene_data_provider=None): def get_num_envs() -> int: return 4 + @staticmethod + def get_contacts(): + return None + def _fake_render_markers(viewer, visible_env_ids, num_envs): marker_calls.append((viewer, visible_env_ids, num_envs)) diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/xr_visualization/check_scene_xr_visualization.py similarity index 98% rename from source/isaaclab/test/visualization/check_scene_xr_visualization.py rename to source/isaaclab/test/xr_visualization/check_scene_xr_visualization.py index 0ecded8048a8..c8d25c51f140 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/xr_visualization/check_scene_xr_visualization.py @@ -9,7 +9,7 @@ .. code-block:: bash # Usage - ./isaaclab.sh -p source/isaaclab/test/visualization/check_scene_visualization.py + ./isaaclab.sh -p source/isaaclab/test/xr_visualization/check_scene_xr_visualization.py """ diff --git a/source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst b/source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst new file mode 100644 index 000000000000..178e170378b7 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst @@ -0,0 +1,5 @@ +Added +^^^^^ + +* Added a ``NewtonManager.get_contacts()`` accessor so visualizers can render + Newton contact buffers without reaching into manager internals. diff --git a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py index d5991ed395ab..41aea04368f4 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py +++ b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py @@ -1584,6 +1584,11 @@ def get_state(cls, scene_data_provider: SceneDataProvider | None = None) -> Stat cls.update_visualization_state(scene_data_provider) return cls.get_state_0() + @classmethod + def get_contacts(cls) -> Contacts | None: + """Get the current Newton contact buffer, if the active solver exposes one.""" + return cls._contacts + @classmethod def get_num_envs(cls) -> int: return cls._num_envs diff --git a/source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst b/source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst new file mode 100644 index 000000000000..ceab9cc95ca3 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed excessive PhysX tensor warnings from Ant tasks with ``JointWrenchSensor`` + by sourcing scene-data transforms for articulation links from Isaac Lab + articulation views instead of a global PhysX rigid-body view. diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index df30c9e268a7..36701a248f5f 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -173,9 +173,10 @@ def simulation_view(self, simulation_view: omni.physics.tensors.SimulationView | def get_rigid_body_view(self) -> omni.physics.tensors.RigidBodyView | None: """Lazily create a rigid body view covering all rigid bodies in the scene. - Discovers rigid body prims by traversing the USD stage and converts - per-environment paths (``/World/envs/env_N/...``) into wildcard - patterns so a single PhysX view covers every environment instance. + Discovers exact rigid body prims by traversing USD, then compacts cloned + environment paths into wildcard patterns. If a rigid body name is also + used by a non-rigid prim, the exact path is kept to avoid PhysX resolving + the wildcard to the non-rigid prim. """ if self._rigid_body_view is not None: return self._rigid_body_view @@ -187,15 +188,29 @@ def get_rigid_body_view(self) -> omni.physics.tensors.RigidBodyView | None: if stage is None: return None - patterns: set[str] = set() + rigid_body_paths: list[str] = [] + non_rigid_body_names: set[str] = set() for prim in stage.Traverse(): + prim_path = prim.GetPath().pathString if prim.HasAPI(UsdPhysics.RigidBodyAPI): - patterns.add(re.sub(r"/World/envs/env_\d+", "/World/envs/env_*", prim.GetPath().pathString)) + rigid_body_paths.append(prim_path) + elif re.search(r"/World/envs/env_\d+/", prim_path): + non_rigid_body_names.add(prim_path.rsplit("/", 1)[-1]) - if not patterns: + patterns: set[str] = set() + exact_paths: list[str] = [] + for prim_path in rigid_body_paths: + body_name = prim_path.rsplit("/", 1)[-1] + if body_name in non_rigid_body_names: + exact_paths.append(prim_path) + else: + patterns.add(re.sub(r"/World/envs/env_\d+", "/World/envs/env_*", prim_path)) + + body_paths = [*sorted(patterns), *exact_paths] + if not body_paths: return None - self._rigid_body_view = self._simulation_view.create_rigid_body_view(list(patterns)) + self._rigid_body_view = self._simulation_view.create_rigid_body_view(body_paths) return self._rigid_body_view @property diff --git a/source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst b/source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst new file mode 100644 index 000000000000..255a3a270ceb --- /dev/null +++ b/source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed Newton visualizer contact rendering by logging Newton contact buffers + when available and falling back to scene contact sensors for PhysX-backed + scenes. diff --git a/source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst b/source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst new file mode 100644 index 000000000000..bcbbbafcebcc --- /dev/null +++ b/source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst @@ -0,0 +1,15 @@ +Fixed +^^^^^ + +* Fixed Newton visualizer HUD dependency checks by requiring + ``typing-extensions>=4.15.0`` for the Newton visualizer extra and failing + integration tests when Newton reports that ``imgui_bundle`` could not be + imported. Removed the legacy ``setup.py`` for ``isaaclab_visualizers`` now that + ``pyproject.toml`` carries the package metadata. + +* Fixed Rerun and Viser visualizers rendering Newton infinite ground planes too + small by expanding non-positive plane extents to the same large finite size + used by Newton GL. + +* Fixed Viser visualizer ground-grid flickering by reusing unchanged plane grid + line segments instead of removing and re-adding them every frame. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index 7c4f82234d0f..3dbecdec794f 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -13,6 +13,7 @@ import sys from typing import TYPE_CHECKING +import torch import warp as wp from newton.viewer import ViewerGL from pyglet.math import Vec3 as PygletVec3 @@ -37,6 +38,15 @@ logger = logging.getLogger(__name__) +CONTACT_ARROW_PATH = "/contacts" +"""Viewer path used for native and synthesized contact arrows.""" + +CONTACT_ARROW_COLOR = (0.0, 1.0, 0.0) +"""Color used by Newton's native contact visualization.""" + +CONTACT_ARROW_LENGTH = 0.1 +"""Length of synthesized contact arrows in meters.""" + if TYPE_CHECKING: from isaaclab.scene_data import SceneDataProvider @@ -488,6 +498,11 @@ def step(self, dt: float) -> None: if hasattr(body_q, "shape") and body_q.shape[0] == 0: return self._viewer.log_state(self._state) + contacts = NewtonManager.get_contacts() + if contacts is not None: + self._viewer.log_contacts(contacts, self._state) + else: + self._log_scene_contact_sensor_arrows(num_envs) if self.cfg.enable_markers: render_newton_visualization_markers( self._viewer, self._resolved_visible_env_ids, num_envs=num_envs @@ -511,6 +526,115 @@ def close(self) -> None: self._camera_sensor = None self._is_closed = True + def _log_scene_contact_sensor_arrows(self, num_envs: int) -> None: + """Render contact sensor data as Newton-style arrows when native contacts are unavailable.""" + if self._viewer is None: + return + if not self._viewer.show_contacts: + self._viewer.log_arrows(CONTACT_ARROW_PATH, None, None, None) + return + contact_sensors = ( + self._scene_data_provider.get_contact_sensors() if self._scene_data_provider is not None else {} + ) + if not contact_sensors: + self._viewer.log_arrows(CONTACT_ARROW_PATH, None, None, None) + return + + starts: list[torch.Tensor] = [] + ends: list[torch.Tensor] = [] + for sensor in contact_sensors.values(): + sensor_starts, sensor_ends = self._contact_sensor_arrow_tensors(sensor, num_envs) + if sensor_starts is not None and sensor_ends is not None: + starts.append(sensor_starts) + ends.append(sensor_ends) + + if not starts: + self._viewer.log_arrows(CONTACT_ARROW_PATH, None, None, None) + return + + starts_t = torch.cat(starts, dim=0).detach().to(dtype=torch.float32, device="cpu").contiguous() + ends_t = torch.cat(ends, dim=0).detach().to(dtype=torch.float32, device="cpu").contiguous() + self._viewer.log_arrows( + CONTACT_ARROW_PATH, + wp.array(starts_t.numpy(), dtype=wp.vec3, device=self._viewer.device), + wp.array(ends_t.numpy(), dtype=wp.vec3, device=self._viewer.device), + CONTACT_ARROW_COLOR, + ) + + def _contact_sensor_arrow_tensors(self, sensor, num_envs: int) -> tuple[torch.Tensor | None, torch.Tensor | None]: + """Build Newton-style arrow starts/ends from an Isaac Lab contact sensor.""" + try: + data = sensor.data + net_forces_proxy = data.net_forces_w + net_forces = net_forces_proxy.torch if net_forces_proxy is not None else None + except (AttributeError, NotImplementedError, RuntimeError): + return None, None + + if net_forces is None or net_forces.numel() == 0: + return None, None + net_forces = self._filter_visible_env_tensor(net_forces, num_envs) + + force_threshold = getattr(getattr(sensor, "cfg", None), "force_threshold", None) + if force_threshold is None: + force_threshold = 0.0 + + try: + contact_pos = getattr(data, "contact_pos_w", None) + force_matrix = getattr(data, "force_matrix_w", None) + except NotImplementedError: + contact_pos = None + force_matrix = None + if contact_pos is not None and force_matrix is not None: + contact_pos_t = self._filter_visible_env_tensor(contact_pos.torch, num_envs) + force_matrix_t = self._filter_visible_env_tensor(force_matrix.torch, num_envs) + if contact_pos_t.numel() != 0 and force_matrix_t.numel() != 0: + force_norm = torch.linalg.norm(force_matrix_t, dim=-1) + finite_pos = torch.isfinite(contact_pos_t).all(dim=-1) + active = (force_norm > force_threshold) & finite_pos + if torch.any(active): + starts = contact_pos_t[active] + directions = torch.nn.functional.normalize(force_matrix_t[active], dim=-1) + return starts, starts + directions * CONTACT_ARROW_LENGTH + + origins = self._contact_sensor_origin_positions(sensor, data, net_forces) + if origins is None: + return None, None + origins = self._filter_visible_env_tensor(origins, num_envs) + + force_norm = torch.linalg.norm(net_forces, dim=-1) + active = force_norm > force_threshold + if not torch.any(active): + return None, None + + starts = origins[active] + directions = torch.nn.functional.normalize(net_forces[active], dim=-1) + return starts, starts + directions * CONTACT_ARROW_LENGTH + + def _contact_sensor_origin_positions(self, sensor, data, net_forces: torch.Tensor) -> torch.Tensor | None: + """Return per-sensor origins for contact arrow starts.""" + try: + pos_w = getattr(data, "pos_w", None) + except NotImplementedError: + pos_w = None + if pos_w is not None: + return pos_w.torch + + body_physx_view = getattr(sensor, "body_physx_view", None) + if body_physx_view is None: + return None + try: + pose = body_physx_view.get_transforms() + except RuntimeError: + return None + return wp.to_torch(pose).view(*net_forces.shape[:-1], 7)[..., :3] + + def _filter_visible_env_tensor(self, tensor: torch.Tensor, num_envs: int) -> torch.Tensor: + """Apply Newton visualizer visible-world filtering to a sensor tensor.""" + if self._resolved_visible_env_ids is None or tensor.ndim == 0 or tensor.shape[0] != num_envs: + return tensor + ids = torch.as_tensor(self._resolved_visible_env_ids, dtype=torch.long, device=tensor.device) + return tensor.index_select(0, ids) + def is_running(self) -> bool: """Return whether the visualizer should continue stepping. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton_adapter.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton_adapter.py index 6bc3d5a2b4f1..8a1554a253fd 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton_adapter.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton_adapter.py @@ -7,6 +7,52 @@ from __future__ import annotations +from collections.abc import Callable +from typing import Any + +VISUALIZER_INFINITE_PLANE_SIZE = 1000.0 +"""Finite render size used for Newton planes encoded as infinite.""" + + +def expand_infinite_plane_scale( + geo_scale: tuple[float, ...], plane_size: float = VISUALIZER_INFINITE_PLANE_SIZE +) -> tuple[float, ...]: + """Return a finite visual scale for Newton planes encoded with non-positive extents. + + Newton uses non-positive X/Y plane scale values to represent an effectively + infinite plane. Newton GL renders those with a large finite mesh; web viewers + also need a finite size, otherwise their world-extents heuristic can shrink + the floor to just the actor bounds. + """ + scale = tuple(float(value) for value in geo_scale) + width = scale[0] if len(scale) > 0 else 0.0 + length = scale[1] if len(scale) > 1 else 0.0 + if width > 0.0 and length > 0.0: + return scale + tail = scale[2:] if len(scale) > 2 else () + return ( + width if width > 0.0 else float(plane_size), + length if length > 0.0 else float(plane_size), + *tail, + ) + + +def log_geo_with_expanded_plane_scale( + super_log_geo: Callable[..., Any], + plane_geo_type: int, + name: str, + geo_type: int, + geo_scale: tuple[float, ...], + geo_thickness: float, + geo_is_solid: bool, + geo_src=None, + hidden: bool = False, +): + """Log geometry after expanding Newton infinite-plane extents for web viewers.""" + if geo_type == plane_geo_type: + geo_scale = expand_infinite_plane_scale(geo_scale) + return super_log_geo(name, geo_type, geo_scale, geo_thickness, geo_is_solid, geo_src, hidden) + def resolve_visible_env_indices( env_ids: list[int] | None, diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py index 8b9eea880813..631ae43c7168 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/rerun/rerun_visualizer.py @@ -16,6 +16,7 @@ from typing import TYPE_CHECKING from urllib.parse import quote +import newton import rerun as rr import rerun.blueprint as rrb from newton.viewer import ViewerRerun @@ -23,7 +24,11 @@ from isaaclab.visualizers.base_visualizer import BaseVisualizer from isaaclab_visualizers.newton.newton_visualization_markers import render_newton_visualization_markers -from isaaclab_visualizers.newton_adapter import apply_viewer_visible_worlds, resolve_visible_env_indices +from isaaclab_visualizers.newton_adapter import ( + apply_viewer_visible_worlds, + log_geo_with_expanded_plane_scale, + resolve_visible_env_indices, +) from .rerun_visualizer_cfg import RerunVisualizerCfg @@ -134,6 +139,29 @@ def _render_ui(self): if imgui.button("Pause Rendering" if not self._paused_rendering else "Resume Rendering"): self._paused_rendering = not self._paused_rendering + def log_geo( + self, + name: str, + geo_type: int, + geo_scale: tuple[float, ...], + geo_thickness: float, + geo_is_solid: bool, + geo_src=None, + hidden: bool = False, + ): + """Log geometry, preserving large render extents for infinite ground planes.""" + return log_geo_with_expanded_plane_scale( + super().log_geo, + newton.GeoType.PLANE, + name, + geo_type, + geo_scale, + geo_thickness, + geo_is_solid, + geo_src, + hidden, + ) + class RerunVisualizer(BaseVisualizer): """Rerun visualizer for Isaac Lab.""" diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py index 5bd9a831adce..17611db34b6e 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/viser/viser_visualizer.py @@ -16,12 +16,18 @@ from pathlib import Path from typing import TYPE_CHECKING, Any +import newton +import numpy as np from newton.viewer import ViewerViser from isaaclab.visualizers.base_visualizer import BaseVisualizer from isaaclab_visualizers.newton.newton_visualization_markers import render_newton_visualization_markers -from isaaclab_visualizers.newton_adapter import apply_viewer_visible_worlds, resolve_visible_env_indices +from isaaclab_visualizers.newton_adapter import ( + apply_viewer_visible_worlds, + log_geo_with_expanded_plane_scale, + resolve_visible_env_indices, +) from .viser_visualizer_cfg import ViserVisualizerCfg @@ -108,12 +114,85 @@ def _viser_server_with_bind_address(*args, **kwargs): record_to_viser=record_to_viser, ) self._metadata = metadata or {} + self._isaaclab_plane_grid_cache: dict[str, tuple] = {} @property def share_url(self) -> str | None: """Return the public share URL created by Viser, if any.""" return self._share_url + def clear_model(self) -> None: + """Clear cached static plane-grid signatures with the viewer model.""" + cache = getattr(self, "_isaaclab_plane_grid_cache", None) + if cache is not None: + cache.clear() + return super().clear_model() + + @staticmethod + def _array_signature(array) -> tuple[tuple[int, ...], bytes] | None: + """Return a stable signature for small transform/scale arrays.""" + if array is None: + return None + array_np = np.ascontiguousarray(np.asarray(array, dtype=np.float32)) + return tuple(int(dim) for dim in array_np.shape), array_np.tobytes() + + def _log_plane_instances( + self, + name: str, + plane_info: dict[str, float | bool], + xforms, + scales, + hidden: bool = False, + ) -> None: + """Avoid removing/re-adding unchanged Viser plane grids every frame.""" + cache = getattr(self, "_isaaclab_plane_grid_cache", None) + if hidden or xforms is None: + if cache is not None: + cache.pop(name, None) + return super()._log_plane_instances(name, plane_info, xforms, scales, hidden=hidden) + + xforms_np = self._to_numpy(xforms) + if xforms_np is None or len(xforms_np) == 0: + if cache is not None: + cache.pop(name, None) + return super()._log_plane_instances(name, plane_info, xforms, scales, hidden=hidden) + + scales_np = self._to_numpy(scales) if scales is not None else None + signature = ( + float(plane_info["width"]), + float(plane_info["length"]), + self._array_signature(xforms_np), + self._array_signature(scales_np), + ) + if cache is not None and cache.get(name) == signature and name in self._plane_handles: + return None + if cache is not None: + cache[name] = signature + return super()._log_plane_instances(name, plane_info, xforms, scales, hidden=hidden) + + def log_geo( + self, + name: str, + geo_type: int, + geo_scale: tuple[float, ...], + geo_thickness: float, + geo_is_solid: bool, + geo_src=None, + hidden: bool = False, + ): + """Log geometry, preserving large render extents for infinite ground planes.""" + return log_geo_with_expanded_plane_scale( + super().log_geo, + newton.GeoType.PLANE, + name, + geo_type, + geo_scale, + geo_thickness, + geo_is_solid, + geo_src, + hidden, + ) + class ViserVisualizer(BaseVisualizer): """Viser web-based visualizer backed by Newton's ViewerViser.""" diff --git a/source/isaaclab_visualizers/pyproject.toml b/source/isaaclab_visualizers/pyproject.toml index 77396b839fad..e39c6f7f943c 100644 --- a/source/isaaclab_visualizers/pyproject.toml +++ b/source/isaaclab_visualizers/pyproject.toml @@ -32,10 +32,12 @@ newton = [ "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", "PyOpenGL-accelerate", "imgui-bundle>=1.92.5", + "typing-extensions>=4.15.0", ] rerun = [ "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", "rerun-sdk>=0.29.0", + "pyarrow==22.0.0", ] viser = [ "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", @@ -45,7 +47,10 @@ all = [ "imgui-bundle>=1.92.5", "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", "PyOpenGL-accelerate", + # Match rerun-sdk's supported Arrow stack and avoid resolver drift across environments. + "pyarrow==22.0.0", "rerun-sdk>=0.29.0", + "typing-extensions>=4.15.0", "viser>=1.0.16", "warp-lang", ] diff --git a/source/isaaclab_visualizers/test/test_newton_adapter.py b/source/isaaclab_visualizers/test/test_newton_adapter.py index 3c020a8d10ee..50d76902d3f0 100644 --- a/source/isaaclab_visualizers/test/test_newton_adapter.py +++ b/source/isaaclab_visualizers/test/test_newton_adapter.py @@ -3,11 +3,63 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Unit tests for viewer env resolution helpers.""" +"""Unit tests for Newton viewer adapter helpers.""" from __future__ import annotations -from isaaclab_visualizers.newton_adapter import apply_viewer_visible_worlds, resolve_visible_env_indices +from types import SimpleNamespace + +import torch +from isaaclab_visualizers.newton import NewtonVisualizer, NewtonVisualizerCfg +from isaaclab_visualizers.newton_adapter import ( + VISUALIZER_INFINITE_PLANE_SIZE, + apply_viewer_visible_worlds, + expand_infinite_plane_scale, + log_geo_with_expanded_plane_scale, + resolve_visible_env_indices, +) + + +def test_expand_infinite_plane_scale_expands_non_positive_extents(): + assert expand_infinite_plane_scale((0.0, 0.0, 1.0, 0.0)) == ( + VISUALIZER_INFINITE_PLANE_SIZE, + VISUALIZER_INFINITE_PLANE_SIZE, + 1.0, + 0.0, + ) + assert expand_infinite_plane_scale((-1.0, 25.0)) == ( + VISUALIZER_INFINITE_PLANE_SIZE, + 25.0, + ) + assert expand_infinite_plane_scale((25.0, 0.0)) == ( + 25.0, + VISUALIZER_INFINITE_PLANE_SIZE, + ) + + +def test_expand_infinite_plane_scale_preserves_finite_extents(): + assert expand_infinite_plane_scale((100.0, 50.0, 1.0)) == (100.0, 50.0, 1.0) + + +def test_log_geo_with_expanded_plane_scale_delegates_with_adjusted_plane_scale(): + calls = [] + + def _log_geo(*args): + calls.append(args) + return "logged" + + assert log_geo_with_expanded_plane_scale(_log_geo, 1, "ground", 1, (0.0, 25.0), 0.0, True) == "logged" + assert calls == [("ground", 1, (VISUALIZER_INFINITE_PLANE_SIZE, 25.0), 0.0, True, None, False)] + + +def test_log_geo_with_expanded_plane_scale_preserves_non_plane_scale(): + calls = [] + + def _log_geo(*args): + calls.append(args) + + log_geo_with_expanded_plane_scale(_log_geo, 1, "box", 2, (0.0, 25.0), 0.0, True, hidden=True) + assert calls == [("box", 2, (0.0, 25.0), 0.0, True, None, True)] def test_resolve_visible_env_indices_truncates_explicit_list(): @@ -47,3 +99,127 @@ def set_visible_worlds(self, worlds): apply_viewer_visible_worlds(_V(), env_ids=None, max_visible_envs=None, num_envs=3) assert calls[-1] is None + + +class _BodyQ: + shape = (1,) + + +class _Viewer: + _update_frequency = 1 + + def __init__(self): + self.device = "cpu" + self.show_contacts = False + self.logged_state = None + self.logged_contacts = None + self.logged_arrows = None + + def is_paused(self): + return False + + def begin_frame(self, _time): + pass + + def log_state(self, state): + self.logged_state = state + + def log_contacts(self, contacts, state): + self.logged_contacts = (contacts, state) + + def log_arrows(self, name, starts, ends, colors): + self.logged_arrows = (name, starts, ends, colors) + + def end_frame(self): + pass + + +class _Proxy: + def __init__(self, tensor): + self.torch = tensor + + +class _ContactSensorData: + def __init__(self, net_forces_w, pos_w): + self.net_forces_w = _Proxy(net_forces_w) + self.pos_w = _Proxy(pos_w) + self.contact_pos_w = None + self.force_matrix_w = None + + +class _ContactSensor: + def __init__(self, net_forces_w, pos_w, force_threshold=1.0): + self.cfg = SimpleNamespace(force_threshold=force_threshold) + self.data = _ContactSensorData(net_forces_w, pos_w) + + +class _SceneDataProvider: + def __init__(self, contact_sensors=None): + self._contact_sensors = contact_sensors or {} + + def get_contact_sensors(self): + return self._contact_sensors + + +def _make_newton_visualizer(viewer, scene_data_provider=None): + visualizer = NewtonVisualizer.__new__(NewtonVisualizer) + visualizer.cfg = NewtonVisualizerCfg(enable_markers=False) + visualizer._is_initialized = True + visualizer._is_closed = False + visualizer._sim_time = 0.0 + visualizer._step_counter = 0 + visualizer._viewer = viewer + visualizer._state = None + visualizer._scene_data_provider = scene_data_provider + visualizer._resolved_visible_env_ids = None + visualizer._log_camera_sensor_image = lambda: None + return visualizer + + +def test_newton_visualizer_logs_native_contacts_when_available(monkeypatch): + from isaaclab_newton.physics import NewtonManager + + state = SimpleNamespace(body_q=_BodyQ()) + contacts = object() + viewer = _Viewer() + + monkeypatch.setattr(NewtonManager, "get_state", lambda _scene_data_provider=None: state) + monkeypatch.setattr(NewtonManager, "get_contacts", lambda: contacts) + monkeypatch.setattr(NewtonManager, "get_num_envs", lambda: 1) + + _make_newton_visualizer(viewer).step(0.1) + + assert viewer.logged_state is state + assert viewer.logged_contacts == (contacts, state) + + +def test_newton_visualizer_contact_sensor_fallback_obeys_show_contacts(monkeypatch): + from isaaclab_newton.physics import NewtonManager + + state = SimpleNamespace(body_q=_BodyQ()) + viewer = _Viewer() + sensor = _ContactSensor( + net_forces_w=torch.tensor([[[0.0, 0.0, 2.0], [0.0, 0.0, 0.5]]], dtype=torch.float32), + pos_w=torch.tensor([[[1.0, 2.0, 3.0], [4.0, 5.0, 6.0]]], dtype=torch.float32), + force_threshold=1.0, + ) + scene_data_provider = _SceneDataProvider({"contact_forces": sensor}) + + monkeypatch.setattr(NewtonManager, "get_state", lambda _scene_data_provider=None: state) + monkeypatch.setattr(NewtonManager, "get_contacts", lambda: None) + monkeypatch.setattr(NewtonManager, "get_num_envs", lambda: 1) + + visualizer = _make_newton_visualizer(viewer, scene_data_provider) + visualizer.step(0.1) + assert viewer.logged_arrows == ("/contacts", None, None, None) + + viewer.show_contacts = True + visualizer.step(0.1) + + name, starts, ends, colors = viewer.logged_arrows + assert name == "/contacts" + assert len(starts) == 1 + assert len(ends) == 1 + assert colors == (0.0, 1.0, 0.0) + assert torch.allclose(torch.tensor(starts.numpy()[0]), torch.tensor([1.0, 2.0, 3.0])) + assert torch.allclose(torch.tensor(ends.numpy()[0]), torch.tensor([1.0, 2.0, 3.1])) diff --git a/source/isaaclab_visualizers/test/test_visualizer_integration_newton.py b/source/isaaclab_visualizers/test/test_visualizer_integration_newton.py index a5567735e5cf..ea8e35fab1ae 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_integration_newton.py +++ b/source/isaaclab_visualizers/test/test_visualizer_integration_newton.py @@ -28,9 +28,12 @@ pytestmark = [pytest.mark.isaacsim_ci, pytest.mark.flaky(max_runs=2, min_passes=1)] -def test_cartpole_env_visualizers_motion_with_play_pause_newton(caplog: pytest.LogCaptureFixture) -> None: +def test_cartpole_env_visualizers_motion_with_play_pause_newton( + caplog: pytest.LogCaptureFixture, capsys: pytest.CaptureFixture[str] +) -> None: """Cartpole env + all non-tiled visualizers on Newton MJWarp.""" run_cartpole_env_visualizers_motion_with_play_pause("newton", caplog) + _viz_utils.assert_no_newton_imgui_bundle_warning(capsys, caplog) if __name__ == "__main__": diff --git a/source/isaaclab_visualizers/test/test_visualizer_integration_physx.py b/source/isaaclab_visualizers/test/test_visualizer_integration_physx.py index dac89b283b00..c8b909ab532e 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_integration_physx.py +++ b/source/isaaclab_visualizers/test/test_visualizer_integration_physx.py @@ -28,9 +28,12 @@ pytestmark = [pytest.mark.isaacsim_ci, pytest.mark.flaky(max_runs=2, min_passes=1)] -def test_cartpole_env_visualizers_motion_with_play_pause_physx(caplog: pytest.LogCaptureFixture) -> None: +def test_cartpole_env_visualizers_motion_with_play_pause_physx( + caplog: pytest.LogCaptureFixture, capsys: pytest.CaptureFixture[str] +) -> None: """Cartpole env + all non-tiled visualizers on PhysX.""" run_cartpole_env_visualizers_motion_with_play_pause("physx", caplog) + _viz_utils.assert_no_newton_imgui_bundle_warning(capsys, caplog) if __name__ == "__main__": diff --git a/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_newton.py b/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_newton.py index e77ee9be05b5..0baaf7d8d5f7 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_newton.py +++ b/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_newton.py @@ -28,9 +28,12 @@ pytestmark = [pytest.mark.isaacsim_ci, pytest.mark.flaky(max_runs=2, min_passes=1)] -def test_visualizer_tiled_integration_newton(caplog: pytest.LogCaptureFixture) -> None: +def test_visualizer_tiled_integration_newton( + caplog: pytest.LogCaptureFixture, capsys: pytest.CaptureFixture[str] +) -> None: """Cartpole env + tiled Kit/Newton visualizers on Newton MJWarp.""" run_cartpole_env_visualizers_tiled_camera_motion("newton", caplog) + _viz_utils.assert_no_newton_imgui_bundle_warning(capsys, caplog) if __name__ == "__main__": diff --git a/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_physx.py b/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_physx.py index 5693c1131ee0..bafffe831e02 100644 --- a/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_physx.py +++ b/source/isaaclab_visualizers/test/test_visualizer_tiled_integration_physx.py @@ -28,9 +28,12 @@ pytestmark = [pytest.mark.isaacsim_ci, pytest.mark.flaky(max_runs=2, min_passes=1)] -def test_visualizer_tiled_integration_physx(caplog: pytest.LogCaptureFixture) -> None: +def test_visualizer_tiled_integration_physx( + caplog: pytest.LogCaptureFixture, capsys: pytest.CaptureFixture[str] +) -> None: """Cartpole env + tiled Kit/Newton visualizers on PhysX.""" run_cartpole_env_visualizers_tiled_camera_motion("physx", caplog) + _viz_utils.assert_no_newton_imgui_bundle_warning(capsys, caplog) if __name__ == "__main__": diff --git a/source/isaaclab_visualizers/test/visualizer_integration_utils.py b/source/isaaclab_visualizers/test/visualizer_integration_utils.py index 8cc79b5ba08b..3b4bc8f3449d 100644 --- a/source/isaaclab_visualizers/test/visualizer_integration_utils.py +++ b/source/isaaclab_visualizers/test/visualizer_integration_utils.py @@ -61,6 +61,7 @@ # When True, tests also fail on WARNING-level records from visualizer-related loggers. ASSERT_VISUALIZER_WARNINGS = False +_NEWTON_IMGUI_BUNDLE_PRINT_WARNING = "Warning: imgui_bundle not found" _MAX_FRAME_CHECK_STEPS = 5 """Steps for Rerun / Viser smoke tests.""" @@ -221,6 +222,19 @@ def _assert_no_visualizer_log_issues(caplog: pytest.LogCaptureFixture, *, fail_o ) +def assert_no_newton_imgui_bundle_warning(capsys: pytest.CaptureFixture[str], caplog: pytest.LogCaptureFixture) -> None: + """Fail when Newton reports that its imgui HUD dependency is missing.""" + captured = capsys.readouterr() + captured_output = captured.out + captured.err + printed_warning = _NEWTON_IMGUI_BUNDLE_PRINT_WARNING in captured_output + logged_warnings = [record for record in caplog.records if _NEWTON_IMGUI_BUNDLE_PRINT_WARNING in record.getMessage()] + assert not printed_warning and not logged_warnings, ( + "Newton viewer reported that imgui_bundle could not be imported, which disables HUD controls. " + f"Captured output: {captured_output!r}. " + "Captured logs: " + "; ".join(f"{record.name}: {record.getMessage()}" for record in logged_warnings) + ) + + def _configure_sim_for_visualizer_test(env: CartpoleCameraEnv) -> None: """Settings used by the previous smoke tests; keep RTX sensors enabled for camera paths.""" AppLauncher.apply_rtx_determinism_settings() diff --git a/tools/wheel_builder/res/python_packages.toml b/tools/wheel_builder/res/python_packages.toml index 24867efd8561..998dc8a05de3 100644 --- a/tools/wheel_builder/res/python_packages.toml +++ b/tools/wheel_builder/res/python_packages.toml @@ -106,7 +106,7 @@ pyproject.optional-dependencies.all = [ { "rsl-rl" = ["rsl-rl-lib==5.0.1", "onnxscript>=0.5"] }, { "rsl_rl" = ["rsl-rl-lib==5.0.1", "onnxscript>=0.5"] }, # ================================================================================ - # https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_visualizers/setup.py + # https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_visualizers/pyproject.toml # ================================================================================ # Viser visualizer (opt-in: viser pulls websockets>=13.1 which collides with # isaacsim-kernel==6.0.0.0's websockets==12.0; do not include in [all]). From 8bbb038c8ea3090c83062fec59c08a2ffa282203 Mon Sep 17 00:00:00 2001 From: ooctipus Date: Fri, 5 Jun 2026 18:23:12 -0700 Subject: [PATCH 04/40] Validate typed presets resolve against their backend during Hydra resolution (#5944) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Summary alternative to #5939 - Selecting a typed preset (e.g. `presets=newton_mjwarp`) on a task that does **not** declare that name on a `PhysicsCfg`/`RendererCfg` previously created a silent mixed configuration: the name would match an unrelated scalar/sensor preset that happens to share the name, tuning those fields while leaving the real backend (e.g. PhysX) untouched. This adds a post-resolution check that a selected *reserved* typed name actually landed on a config of its own type at least once, and raises a clear `ValueError` otherwise. - The set of reserved canonical names is declared per typed target in `PresetTarget` (`preset_target.py`) — `PHYSICS = {newton_mjwarp, newton_kamino}`, plus the known renderer backends. New solvers/renderers opt in by adding their name there; the resolver hardcodes nothing. `physx`/`ovphysx` are intentionally **not** reserved (PhysX is the default backend, so selecting it on a task without a physics preset is harmless rather than a silent mismatch). - Implementation is minimal: one `typed_hits: set[str]` threaded through `_pick_alternative`/`_resolve_active_presets` records when a reserved name resolves to a value of its target type; `_validate_typed_presets` then flags `reserved-selected ∩ consumed − typed_hits`. Truly-unknown names continue to flow to the existing "Unknown preset(s)" error path. ## Behavior | Invocation | Result | |---|---| | `Isaac-Velocity-Flat-Anymal-C-v0 presets=newton_mjwarp` | resolves (lands on `NewtonCfg`) | | `Isaac-Navigation-Flat-Anymal-C-v0 presets=newton_mjwarp` | `ValueError` (no Newton physics; only matched a sensor/scalar) | | `Isaac-Navigation-Flat-Anymal-C-v0 presets=physx` | resolves (PhysX not reserved, benign) | | `Isaac-Navigation-Flat-Anymal-C-v0 presets=newton_kamino` | "Unknown preset(s)" (unchanged path) | | legacy alias `presets=newton` on navigation | `ValueError` (canonicalized to `newton_mjwarp`) | ## Test plan - [x] `./isaaclab.sh -p -m pytest source/isaaclab_tasks/test/core/test_hydra.py` (added 7 regression tests for the validator + end-to-end resolution; full file passes) - [x] `test_preset_cli.py`, `test_newton_solver_preset_names.py`, `test_preset_kit_decision.py` pass - [x] Config-resolution probes for the table above - [x] `pre-commit` (ruff/format/codespell/rst/license) green - [ ] CI A changelog fragment is included under `source/isaaclab_tasks/changelog.d/`. --- scripts/benchmarks/benchmark_non_rl.py | 3 +- scripts/benchmarks/benchmark_rlgames.py | 3 +- scripts/benchmarks/benchmark_rsl_rl.py | 3 +- scripts/benchmarks/benchmark_startup.py | 3 +- scripts/environments/random_agent.py | 3 +- scripts/environments/zero_agent.py | 3 +- .../leapp/rsl_rl/export.py | 7 +- .../reinforcement_learning/rl_games/play.py | 3 +- .../rl_games/play_rl_games.py | 3 +- .../reinforcement_learning/rl_games/train.py | 3 +- .../rl_games/train_rl_games.py | 8 +- scripts/reinforcement_learning/rsl_rl/play.py | 3 +- .../rsl_rl/play_rsl_rl.py | 3 +- .../reinforcement_learning/rsl_rl/train.py | 8 +- .../rsl_rl/train_rsl_rl.py | 6 +- scripts/reinforcement_learning/sb3/play.py | 3 +- .../reinforcement_learning/sb3/play_sb3.py | 3 +- scripts/reinforcement_learning/sb3/train.py | 3 +- .../reinforcement_learning/sb3/train_sb3.py | 8 +- scripts/reinforcement_learning/skrl/play.py | 3 +- .../reinforcement_learning/skrl/play_skrl.py | 3 +- scripts/reinforcement_learning/skrl/train.py | 3 +- .../reinforcement_learning/skrl/train_skrl.py | 8 +- .../test/test_typed_preset_cli_train_play.py | 39 ++-- scripts/sim2sim_transfer/rsl_rl_transfer.py | 4 +- .../fix-hydra-typed-preset-validation.rst | 21 ++ .../isaaclab_tasks/utils/__init__.pyi | 3 +- .../isaaclab_tasks/utils/hydra.py | 69 +++++- .../isaaclab_tasks/utils/preset_cli.py | 106 ++------- source/isaaclab_tasks/test/core/test_hydra.py | 88 ++++++++ .../test/core/test_preset_cli.py | 212 +++--------------- 31 files changed, 280 insertions(+), 358 deletions(-) create mode 100644 source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst diff --git a/scripts/benchmarks/benchmark_non_rl.py b/scripts/benchmarks/benchmark_non_rl.py index a9f61f938ed5..ed8702cfbc7e 100644 --- a/scripts/benchmarks/benchmark_non_rl.py +++ b/scripts/benchmarks/benchmark_non_rl.py @@ -15,7 +15,7 @@ from isaaclab.app import AppLauncher -from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli +from isaaclab_tasks.utils import setup_preset_cli # add argparse arguments parser = argparse.ArgumentParser(description="Train an RL agent with RL-Games.") @@ -50,7 +50,6 @@ # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -hydra_args = fold_preset_tokens(hydra_args) sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/benchmarks/benchmark_rlgames.py b/scripts/benchmarks/benchmark_rlgames.py index 2b19c12ffe29..3cfc417ac769 100644 --- a/scripts/benchmarks/benchmark_rlgames.py +++ b/scripts/benchmarks/benchmark_rlgames.py @@ -15,7 +15,7 @@ from isaaclab.app import AppLauncher -from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli +from isaaclab_tasks.utils import setup_preset_cli from scripts.benchmarks.early_stop import ( RlGamesEarlyStopObserver, @@ -67,7 +67,6 @@ # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -hydra_args = fold_preset_tokens(hydra_args) sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/benchmarks/benchmark_rsl_rl.py b/scripts/benchmarks/benchmark_rsl_rl.py index dcec5d44b1cc..1852034b9e2b 100644 --- a/scripts/benchmarks/benchmark_rsl_rl.py +++ b/scripts/benchmarks/benchmark_rsl_rl.py @@ -15,7 +15,7 @@ from isaaclab.app import AppLauncher -from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli +from isaaclab_tasks.utils import setup_preset_cli from scripts.benchmarks.early_stop import ( RslRlEarlyStopWrapper, @@ -72,7 +72,6 @@ # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -hydra_args = fold_preset_tokens(hydra_args) sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/benchmarks/benchmark_startup.py b/scripts/benchmarks/benchmark_startup.py index 201ecbcebb5d..1f692d7af155 100644 --- a/scripts/benchmarks/benchmark_startup.py +++ b/scripts/benchmarks/benchmark_startup.py @@ -19,7 +19,7 @@ from isaaclab.app import AppLauncher -from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli +from isaaclab_tasks.utils import setup_preset_cli # -- CLI arguments ----------------------------------------------------------- @@ -60,7 +60,6 @@ # append AppLauncher cli args (provides --device, --headless, etc.) AppLauncher.add_app_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -hydra_args = fold_preset_tokens(hydra_args) sys.argv = [sys.argv[0]] + hydra_args sys.path.append(os.path.join(os.path.dirname(os.path.abspath(__file__)), "../..")) diff --git a/scripts/environments/random_agent.py b/scripts/environments/random_agent.py index 42c5d893a5c9..eb4c7042b439 100644 --- a/scripts/environments/random_agent.py +++ b/scripts/environments/random_agent.py @@ -19,7 +19,6 @@ from isaaclab.app import add_launcher_args, launch_simulation from isaaclab_tasks.utils import ( - fold_preset_tokens, resolve_task_config, setup_preset_cli, ) @@ -34,7 +33,7 @@ # append AppLauncher cli args add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args # PLACEHOLDER: Extension template (do not remove this comment) diff --git a/scripts/environments/zero_agent.py b/scripts/environments/zero_agent.py index 10ba6f7d97d2..997eb3a25ded 100644 --- a/scripts/environments/zero_agent.py +++ b/scripts/environments/zero_agent.py @@ -19,7 +19,6 @@ from isaaclab.app import add_launcher_args, launch_simulation from isaaclab_tasks.utils import ( - fold_preset_tokens, resolve_task_config, setup_preset_cli, ) @@ -34,7 +33,7 @@ # append AppLauncher cli args add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args # PLACEHOLDER: Extension template (do not remove this comment) MAX_STEPS = 100 diff --git a/scripts/reinforcement_learning/leapp/rsl_rl/export.py b/scripts/reinforcement_learning/leapp/rsl_rl/export.py index d1f65ca9e044..fedda81cb961 100644 --- a/scripts/reinforcement_learning/leapp/rsl_rl/export.py +++ b/scripts/reinforcement_learning/leapp/rsl_rl/export.py @@ -18,7 +18,7 @@ from isaaclab.app import AppLauncher -from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli +from isaaclab_tasks.utils import setup_preset_cli _RSL_RL_SCRIPTS_DIR = Path(__file__).resolve().parents[2] / "rsl_rl" if str(_RSL_RL_SCRIPTS_DIR) not in sys.path: @@ -363,9 +363,8 @@ def run_export_with_hydra(args_cli: argparse.Namespace, hydra_args: list[str]) - from isaaclab_tasks.utils.hydra import hydra_task_config original_argv = sys.argv - # Fold typed preset selectors into a single ``presets=`` token before - # Hydra reads sys.argv; remainder still carries plain Hydra path overrides. - sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) + # Hydra reads the preset tokens (physics=/renderer=/presets=) from sys.argv directly. + sys.argv = [sys.argv[0]] + hydra_args exported = False try: diff --git a/scripts/reinforcement_learning/rl_games/play.py b/scripts/reinforcement_learning/rl_games/play.py index 73587c93e66c..c214902ea7e8 100644 --- a/scripts/reinforcement_learning/rl_games/play.py +++ b/scripts/reinforcement_learning/rl_games/play.py @@ -40,7 +40,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, resolve_task_config, setup_preset_cli, @@ -77,7 +76,7 @@ parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/reinforcement_learning/rl_games/play_rl_games.py b/scripts/reinforcement_learning/rl_games/play_rl_games.py index 31259e3123c2..4cbf6630d9b2 100644 --- a/scripts/reinforcement_learning/rl_games/play_rl_games.py +++ b/scripts/reinforcement_learning/rl_games/play_rl_games.py @@ -29,7 +29,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, resolve_task_config, setup_preset_cli, @@ -70,7 +69,7 @@ if args_cli.video: args_cli.enable_cameras = True -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args def main(): diff --git a/scripts/reinforcement_learning/rl_games/train.py b/scripts/reinforcement_learning/rl_games/train.py index ac54699b13d1..dda2297ce937 100644 --- a/scripts/reinforcement_learning/rl_games/train.py +++ b/scripts/reinforcement_learning/rl_games/train.py @@ -42,7 +42,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, resolve_task_config, setup_preset_cli, ) @@ -87,7 +86,7 @@ ) add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/reinforcement_learning/rl_games/train_rl_games.py b/scripts/reinforcement_learning/rl_games/train_rl_games.py index 78d7e8ffa802..eb96f62ed87e 100644 --- a/scripts/reinforcement_learning/rl_games/train_rl_games.py +++ b/scripts/reinforcement_learning/rl_games/train_rl_games.py @@ -60,14 +60,14 @@ def _parse_args(argv: list[str]) -> argparse.Namespace: const=True, help="if toggled, this experiment will be tracked with Weights and Biases", ) - from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli + from isaaclab_tasks.utils import setup_preset_cli add_isaaclab_launcher_args(parser) - # setup_preset_cli registers preset-selection help text + runs parse_known_args; - # fold_preset_tokens rewrites typed selectors (physics=, renderer=, presets=) post-argparse. + # setup_preset_cli registers preset-selection help text + runs parse_known_args; the + # physics=/renderer=/presets= tokens pass through the remainder for hydra to parse later. args_cli, hydra_args = setup_preset_cli(parser, argv) enable_cameras_for_video(args_cli) - set_hydra_args(fold_preset_tokens(hydra_args)) + set_hydra_args(hydra_args) return args_cli diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index 8f7d6f6057d9..1bfb19c81d17 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -45,7 +45,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, setup_preset_cli, ) @@ -99,7 +98,7 @@ # intersection are pre-fold (the callback reads the user's original sys.argv), so # preset tokens like ``physics=NAME`` compare correctly here. Fold runs after. remaining_args = list_intersection(remaining_args, remaining_args_env_registration) -sys.argv = [sys.argv[0]] + fold_preset_tokens(remaining_args) +sys.argv = [sys.argv[0]] + remaining_args # Check for installed RSL-RL version installed_version = metadata.version("rsl-rl-lib") diff --git a/scripts/reinforcement_learning/rsl_rl/play_rsl_rl.py b/scripts/reinforcement_learning/rsl_rl/play_rsl_rl.py index 637dff7bfa5e..d4236186f65b 100644 --- a/scripts/reinforcement_learning/rsl_rl/play_rsl_rl.py +++ b/scripts/reinforcement_learning/rsl_rl/play_rsl_rl.py @@ -34,7 +34,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, setup_preset_cli, ) @@ -86,7 +85,7 @@ # The remaining arguments are the arguments that were not consumed by both this scripts # argparser and (optionally) the external callback function. remaining_args = list_intersection(remaining_args, remaining_args_env_registration) -sys.argv = [sys.argv[0]] + fold_preset_tokens(remaining_args) +sys.argv = [sys.argv[0]] + remaining_args # Check for installed RSL-RL version installed_version = metadata.version("rsl-rl-lib") diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index bd30c2612bdc..c9be857d41f5 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -40,7 +40,7 @@ from isaaclab_rl.rsl_rl import RslRlBaseRunnerCfg, RslRlVecEnvWrapper, handle_deprecated_rsl_rl_cfg import isaaclab_tasks # noqa: F401 -from isaaclab_tasks.utils import fold_preset_tokens, get_checkpoint_path, setup_preset_cli +from isaaclab_tasks.utils import get_checkpoint_path, setup_preset_cli from isaaclab_tasks.utils.hydra import hydra_task_config # local imports @@ -97,10 +97,10 @@ # clear out sys.argv for Hydra # The remaining arguments are the arguments that were not consumed by both this scripts # argparser and (optionally) the external callback function. Both sides of this -# intersection are pre-fold (the callback reads the user's original sys.argv), so -# preset tokens like ``physics=NAME`` compare correctly here. Fold runs after. +# intersection share the same token vocabulary (the callback reads the user's +# original sys.argv), so preset tokens like ``physics=NAME`` compare correctly. remaining_args = list_intersection(remaining_args, remaining_args_env_registration) -sys.argv = [sys.argv[0]] + fold_preset_tokens(remaining_args) +sys.argv = [sys.argv[0]] + remaining_args # -- check RSL-RL version ---------------------------------------------------- installed_version = metadata.version("rsl-rl-lib") diff --git a/scripts/reinforcement_learning/rsl_rl/train_rsl_rl.py b/scripts/reinforcement_learning/rsl_rl/train_rsl_rl.py index cacb2691e99c..69b26b1a4e84 100644 --- a/scripts/reinforcement_learning/rsl_rl/train_rsl_rl.py +++ b/scripts/reinforcement_learning/rsl_rl/train_rsl_rl.py @@ -66,7 +66,7 @@ def _parse_args(argv: list[str]) -> argparse.Namespace: """Parse RSL-RL training arguments.""" from isaaclab.utils.string import list_intersection, string_to_callable - from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli + from isaaclab_tasks.utils import setup_preset_cli parser = argparse.ArgumentParser(description="Train an RL agent with RSL-RL.") add_common_train_args( @@ -90,8 +90,8 @@ def _parse_args(argv: list[str]) -> argparse.Namespace: external_callback_function = string_to_callable(args_cli.external_callback, separator=".") remaining_args_env_registration = external_callback_function() - # fold_preset_tokens rewrites typed selectors (physics=, renderer=, presets=) post-argparse - set_hydra_args(fold_preset_tokens(list_intersection(remaining_args, remaining_args_env_registration))) + # physics=/renderer=/presets= tokens pass through the remainder for hydra to parse later + set_hydra_args(list_intersection(remaining_args, remaining_args_env_registration)) return args_cli diff --git a/scripts/reinforcement_learning/sb3/play.py b/scripts/reinforcement_learning/sb3/play.py index 085e7ebd884f..1f21e864bd54 100644 --- a/scripts/reinforcement_learning/sb3/play.py +++ b/scripts/reinforcement_learning/sb3/play.py @@ -38,7 +38,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, resolve_task_config, setup_preset_cli, @@ -81,7 +80,7 @@ ) add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/reinforcement_learning/sb3/play_sb3.py b/scripts/reinforcement_learning/sb3/play_sb3.py index 7a31e2d6fdd3..19ad06c21e29 100644 --- a/scripts/reinforcement_learning/sb3/play_sb3.py +++ b/scripts/reinforcement_learning/sb3/play_sb3.py @@ -27,7 +27,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, resolve_task_config, setup_preset_cli, @@ -74,7 +73,7 @@ if args_cli.video: args_cli.enable_cameras = True -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args def main(): diff --git a/scripts/reinforcement_learning/sb3/train.py b/scripts/reinforcement_learning/sb3/train.py index 5edd661363b3..083cdb6a098b 100644 --- a/scripts/reinforcement_learning/sb3/train.py +++ b/scripts/reinforcement_learning/sb3/train.py @@ -43,7 +43,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, resolve_task_config, setup_preset_cli, ) @@ -80,7 +79,7 @@ ) add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/reinforcement_learning/sb3/train_sb3.py b/scripts/reinforcement_learning/sb3/train_sb3.py index da0af397a865..282c40a255d9 100644 --- a/scripts/reinforcement_learning/sb3/train_sb3.py +++ b/scripts/reinforcement_learning/sb3/train_sb3.py @@ -67,14 +67,14 @@ def _parse_args(argv: list[str]) -> argparse.Namespace: default=False, help="Use a slower SB3 wrapper but keep all the extra training info.", ) - from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli + from isaaclab_tasks.utils import setup_preset_cli add_isaaclab_launcher_args(parser) - # setup_preset_cli registers preset-selection help text + runs parse_known_args; - # fold_preset_tokens rewrites typed selectors (physics=, renderer=, presets=) post-argparse. + # setup_preset_cli registers preset-selection help text + runs parse_known_args; the + # physics=/renderer=/presets= tokens pass through the remainder for hydra to parse later. args_cli, hydra_args = setup_preset_cli(parser, argv) enable_cameras_for_video(args_cli) - set_hydra_args(fold_preset_tokens(hydra_args)) + set_hydra_args(hydra_args) return args_cli diff --git a/scripts/reinforcement_learning/skrl/play.py b/scripts/reinforcement_learning/skrl/play.py index f5128df7b991..4a2d6c369201 100644 --- a/scripts/reinforcement_learning/skrl/play.py +++ b/scripts/reinforcement_learning/skrl/play.py @@ -41,7 +41,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, resolve_task_config, setup_preset_cli, @@ -95,7 +94,7 @@ parser.add_argument("--real-time", action="store_true", default=False, help="Run in real-time, if possible.") add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/reinforcement_learning/skrl/play_skrl.py b/scripts/reinforcement_learning/skrl/play_skrl.py index 3317714f33b2..007759688192 100644 --- a/scripts/reinforcement_learning/skrl/play_skrl.py +++ b/scripts/reinforcement_learning/skrl/play_skrl.py @@ -30,7 +30,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, get_checkpoint_path, resolve_task_config, setup_preset_cli, @@ -88,7 +87,7 @@ if args_cli.video: args_cli.enable_cameras = True -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args # -- check skrl version ------------------------------------------------------ if version.parse(skrl.__version__) < version.parse(SKRL_VERSION): diff --git a/scripts/reinforcement_learning/skrl/train.py b/scripts/reinforcement_learning/skrl/train.py index ab01de2fa0fc..491eded15323 100644 --- a/scripts/reinforcement_learning/skrl/train.py +++ b/scripts/reinforcement_learning/skrl/train.py @@ -44,7 +44,6 @@ import isaaclab_tasks # noqa: F401 from isaaclab_tasks.utils import ( - fold_preset_tokens, resolve_task_config, setup_preset_cli, ) @@ -99,7 +98,7 @@ ) add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/scripts/reinforcement_learning/skrl/train_skrl.py b/scripts/reinforcement_learning/skrl/train_skrl.py index 64acc0268e8b..e63b4172f060 100644 --- a/scripts/reinforcement_learning/skrl/train_skrl.py +++ b/scripts/reinforcement_learning/skrl/train_skrl.py @@ -66,14 +66,14 @@ def _parse_args(argv: list[str]) -> argparse.Namespace: choices=["AMP", "PPO", "IPPO", "MAPPO"], help="The RL algorithm used for training the skrl agent.", ) - from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli + from isaaclab_tasks.utils import setup_preset_cli add_isaaclab_launcher_args(parser) - # setup_preset_cli registers preset-selection help text + runs parse_known_args; - # fold_preset_tokens rewrites typed selectors (physics=, renderer=, presets=) post-argparse. + # setup_preset_cli registers preset-selection help text + runs parse_known_args; the + # physics=/renderer=/presets= tokens pass through the remainder for hydra to parse later. args_cli, hydra_args = setup_preset_cli(parser, argv) enable_cameras_for_video(args_cli) - set_hydra_args(fold_preset_tokens(hydra_args)) + set_hydra_args(hydra_args) return args_cli diff --git a/scripts/reinforcement_learning/test/test_typed_preset_cli_train_play.py b/scripts/reinforcement_learning/test/test_typed_preset_cli_train_play.py index 362265cebb31..3f870839ffeb 100644 --- a/scripts/reinforcement_learning/test/test_typed_preset_cli_train_play.py +++ b/scripts/reinforcement_learning/test/test_typed_preset_cli_train_play.py @@ -9,22 +9,22 @@ The four supported RL libraries (rl_games, rsl_rl, sb3, skrl) each have a ``train_.py`` / ``play_.py`` script that the unified ``scripts/reinforcement_learning/{train,play}.py`` dispatchers route to via -``--rl_library``. Each entrypoint must wire the typed preset CLI -(``setup_preset_cli`` + ``fold_preset_tokens`` from -:mod:`isaaclab_tasks.utils.preset_cli`) so that user-typed ``physics=NAME`` -/ ``renderer=NAME`` / ``presets=NAME`` tokens are folded into the canonical -form Hydra consumes. Without the fold, those tokens hit Hydra as a struct -override against a non-existent top-level key and raise -``Key 'physics' is not in struct`` -- the original symptom of the #5715 -regression. +``--rl_library``. Each entrypoint must wire :func:`setup_preset_cli` and pass +its remainder through to Hydra so that user-typed ``physics=NAME`` / +``renderer=NAME`` / ``presets=NAME`` tokens reach +:func:`~isaaclab_tasks.utils.hydra.register_task`, which parses them directly. +If an entrypoint dropped the remainder (or routed the token to Hydra as a raw +override), the token would hit Hydra as a struct override against a +non-existent top-level key and raise ``Key 'physics' is not in struct`` -- the +original symptom of the #5715 regression. This test invokes each entrypoint via the unified dispatcher with ``physics=does_not_exist`` and asserts: -* the Hydra struct error is **absent** (would indicate the fold did not - run), and -* the resolver's own ``Unknown preset(s)`` error is **present** (the - fold ran and the resolver received the canonical token). +* the Hydra struct error is **absent** (would indicate the token was not + routed to ``register_task``), and +* the resolver's own ``Unknown preset(s)`` error is **present** (the token + reached the resolver). Resolve fails before any Kit/sim launch, so each subprocess exits in a few seconds without needing GPU. @@ -57,11 +57,10 @@ def test_typed_preset_reaches_resolver(action: str, library: str) -> None: """``physics=`` must reach the resolver, not crash Hydra's struct check. - Confirms that the dispatched entrypoint wired ``setup_preset_cli`` + - ``fold_preset_tokens`` correctly: the typed selector got rewritten into - the canonical ``presets=`` form before Hydra received it, and the - resolver then surfaced its own ``Unknown preset(s)`` error against the - deliberately invalid name. + Confirms that the dispatched entrypoint wired ``setup_preset_cli`` and + passed its remainder through, so the typed selector reached + ``register_task``, which surfaced its own ``Unknown preset(s)`` error + against the deliberately invalid name. """ dispatcher = REPO_ROOT / "scripts" / "reinforcement_learning" / f"{action}.py" assert dispatcher.exists(), f"missing dispatcher: {dispatcher}" @@ -89,13 +88,13 @@ def test_typed_preset_reaches_resolver(action: str, library: str) -> None: label = f"{action}.py --rl_library {library}" assert "is not in struct" not in combined, ( f"{label}: Hydra's struct-override error reached the user, meaning the typed preset " - f"selector was NOT folded before Hydra processed it. The entrypoint must call " - f"setup_preset_cli + fold_preset_tokens before set_hydra_args / sys.argv assignment.\n" + f"selector was routed to Hydra as a raw override instead of register_task. The entrypoint " + f"must call setup_preset_cli and pass its remainder through to set_hydra_args / sys.argv.\n" f"--- stderr tail ---\n{result.stderr[-2000:]}\n" f"--- stdout tail ---\n{result.stdout[-2000:]}\n" ) assert "Unknown preset(s): does_not_exist" in combined, ( - f"{label}: resolver's 'Unknown preset(s)' error did not appear. Either the fold did not " + f"{label}: resolver's 'Unknown preset(s)' error did not appear. Either the token did not " f"reach the resolver, or the script exited earlier with a different error.\n" f"--- stderr tail ---\n{result.stderr[-2000:]}\n" f"--- stdout tail ---\n{result.stdout[-2000:]}\n" diff --git a/scripts/sim2sim_transfer/rsl_rl_transfer.py b/scripts/sim2sim_transfer/rsl_rl_transfer.py index bc5d3a52182b..528d24ded946 100644 --- a/scripts/sim2sim_transfer/rsl_rl_transfer.py +++ b/scripts/sim2sim_transfer/rsl_rl_transfer.py @@ -13,7 +13,7 @@ from isaaclab.app import AppLauncher -from isaaclab_tasks.utils import fold_preset_tokens, setup_preset_cli +from isaaclab_tasks.utils import setup_preset_cli # local imports sys.path.append(os.path.join(os.path.dirname(os.path.abspath(__file__)), "../..")) @@ -45,7 +45,7 @@ # append AppLauncher cli args AppLauncher.add_app_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args if args_cli.video: args_cli.enable_cameras = True diff --git a/source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst b/source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst new file mode 100644 index 000000000000..339a64e4575b --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst @@ -0,0 +1,21 @@ +Added +^^^^^ + +* Added validation for the typed preset selectors ``physics=NAME`` and + ``renderer=NAME`` during Hydra resolution. A typed selector is now enforced + to resolve against a config of that type (a + :class:`~isaaclab.physics.PhysicsCfg` / renderer config) at least once; + selecting one on a task that only exposes the name as an unrelated preset + (e.g. a scalar or sensor variant) raises a descriptive :class:`ValueError` + instead of silently leaving the backend unchanged. The free-form + ``presets=NAME`` broadcast is trusted and not enforced. + +Changed +^^^^^^^ + +* **Breaking:** Removed ``isaaclab_tasks.utils.fold_preset_tokens``. + :func:`~isaaclab_tasks.utils.preset_cli.setup_preset_cli` now returns the + ``physics=`` / ``renderer=`` / ``presets=`` tokens verbatim, and + :func:`~isaaclab_tasks.utils.hydra.register_task` parses them directly. + Scripts assign the remainder to ``sys.argv`` unchanged (drop the + ``fold_preset_tokens(...)`` wrapper). diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/__init__.pyi b/source/isaaclab_tasks/isaaclab_tasks/utils/__init__.pyi index 71fca4e7d71a..bfb7af42f762 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/__init__.pyi +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/__init__.pyi @@ -14,10 +14,9 @@ __all__ = [ "hydra_task_config", "resolve_presets", "setup_preset_cli", - "fold_preset_tokens", ] from .hydra import PresetCfg, preset, hydra_task_config, resolve_task_config, resolve_presets from .importer import import_packages from .parse_cfg import get_checkpoint_path, load_cfg_from_registry, parse_env_cfg -from .preset_cli import fold_preset_tokens, setup_preset_cli +from .preset_cli import setup_preset_cli diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py b/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py index 779e7225ebfc..5d965b7dd332 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py @@ -15,9 +15,11 @@ Override categories (applied in order): 1. Global presets: ``presets=inference,newton_mjwarp`` -- apply everywhere matching - 2. Path presets: ``env.backend=newton_mjwarp`` -- REPLACE specific section - 3. Preset-path scalars: ``env.backend.dt=0.001`` -- handled by us - 4. Global scalars: ``env.decimation=10`` -- handled by Hydra + 2. Typed selectors: ``physics=newton_mjwarp`` / ``renderer=NAME`` -- like a + global preset, but must resolve against a config of that type or it errors + 3. Path presets: ``env.backend=newton_mjwarp`` -- REPLACE specific section + 4. Preset-path scalars: ``env.backend.dt=0.001`` -- handled by us + 5. Global scalars: ``env.decimation=10`` -- handled by Hydra Example usage:: @@ -279,6 +281,7 @@ def _pick_alternative( path: str = "", explicit_name: str | None = None, consumed_selected: set[str] | None = None, + typed_hits: dict[str, set[PresetTarget]] | None = None, ): """Choose the best alternative from a PresetCfg. @@ -310,16 +313,22 @@ def _pick_alternative( name = _normalize_preset_name(raw_name, field_names) if name not in fields or name == match_name: continue + val = fields[name] if consumed_selected is not None: consumed_selected.add(raw_name) consumed_selected.add(name) + if typed_hits is not None: + # record which typed targets (physics/renderer) this name landed on + targets = {t for t in PresetTarget if t.base_classes and isinstance(val, t.base_classes)} + if targets: + typed_hits.setdefault(raw_name, set()).update(targets) + typed_hits.setdefault(name, set()).update(targets) if match_name is not None: - val = fields[name] if match_value is not val and match_value != val: raise ValueError( f"Conflicting global presets: '{match_name}' and '{name}' both define preset for '{path}'" ) - match_name, match_value = name, fields[name] + match_name, match_value = name, val if match_name is not None: return match_value if "default" in fields: @@ -338,6 +347,7 @@ def _resolve_active_presets( *, strict_explicit: bool = True, consumed_selected: set[str] | None = None, + typed_hits: dict[str, set[PresetTarget]] | None = None, consumed_explicit: set[str] | None = None, ): """Resolve presets by walking only the currently active tree. @@ -364,6 +374,7 @@ def resolve_chain(preset_obj: PresetCfg, path: str): path=path, explicit_name=explicit.get(path), consumed_selected=consumed_selected, + typed_hits=typed_hits, ) return val @@ -535,6 +546,36 @@ def _format_unknown_presets_error(unknown: set[str], name_to_paths: dict[str, li return "\n".join(lines) +def _validate_typed_presets( + requested: dict[PresetTarget, set[str]], + typed_hits: dict[str, set[PresetTarget]], +) -> None: + """Check that each typed selector landed on a config of its own type. + + A typed selector (``physics=NAME`` / ``renderer=NAME``) is an explicit + request for a backend of that type, so ``NAME`` must replace at least one + config of that type during resolution. If it only matched unrelated presets + that happen to share the name (a scalar, a sensor variant), the backend + silently stays unchanged, so raise. The free-form ``presets=NAME`` broadcast + is intentionally *not* checked -- there the user makes no typing claim. + + Raises: + ValueError: If a ``physics=`` / ``renderer=`` name never resolved + against a config of that target's type. + """ + aliases = PresetTarget.all_legacy_aliases() + missing = sorted( + (t.value, n) for t, ns in requested.items() for n in ns if t not in typed_hits.get(aliases.get(n, n), set()) + ) + if missing: + clauses = ", ".join(f"{label}={name}" for label, name in missing) + raise ValueError( + f"Typed preset selector(s) {clauses} did not match any preset of that type for this task. " + "The name only matched unrelated presets (or nothing), so the backend would stay unchanged. " + "Use a task that declares it on the matching config, or drop the selector." + ) + + def register_task(task_name: str, agent_entry: str) -> tuple: """Load configs, collect presets recursively, register base config to Hydra. @@ -551,7 +592,12 @@ def register_task(task_name: str, agent_entry: str) -> tuple: env_cfg = load_cfg_from_registry(task_name, "env_cfg_entry_point") agent_cfg = load_cfg_from_registry(task_name, agent_entry) if agent_entry else None + # CLI preset tokens: ``presets=NAME[,...]`` broadcasts (no typing claim), + # while ``physics=NAME`` / ``renderer=NAME`` are typed selectors that must + # resolve against a config of that type (enforced after resolution). + typed_labels = {target.value: target for target in PresetTarget if target.base_classes} global_presets: list[str] = [] + requested_targets: dict[PresetTarget, set[str]] = {} override_items: list[tuple[str, str, str]] = [] hydra_args: list[str] = [] for arg in sys.argv[1:]: @@ -559,13 +605,19 @@ def register_task(task_name: str, agent_entry: str) -> tuple: hydra_args.append(arg) continue key, val = arg.split("=", 1) - if key.lstrip("-") == "presets": + token = key.lstrip("-") + if token == PresetTarget.DOMAIN.value: global_presets.extend(v.strip() for v in val.split(",") if v.strip()) + elif token in typed_labels: + for name in (v.strip() for v in val.split(",") if v.strip()): + global_presets.append(name) + requested_targets.setdefault(typed_labels[token], set()).add(name) else: override_items.append((key, val, arg)) explicit = {key: val for key, val, _arg in override_items} consumed_presets: set[str] = set() + typed_hits: dict[str, set[PresetTarget]] = {} consumed_explicit: set[str] = set() env_explicit = {path: name for path, name in explicit.items() if path == "env" or path.startswith("env.")} agent_explicit = {path: name for path, name in explicit.items() if path == "agent" or path.startswith("agent.")} @@ -576,6 +628,7 @@ def register_task(task_name: str, agent_entry: str) -> tuple: root_path="env", strict_explicit=False, consumed_selected=consumed_presets, + typed_hits=typed_hits, consumed_explicit=consumed_explicit, ) if agent_cfg is not None: @@ -586,6 +639,7 @@ def register_task(task_name: str, agent_entry: str) -> tuple: root_path="agent", strict_explicit=False, consumed_selected=consumed_presets, + typed_hits=typed_hits, consumed_explicit=consumed_explicit, ) @@ -610,6 +664,9 @@ def register_task(task_name: str, agent_entry: str) -> tuple: display = {n: p for n, p in name_to_paths.items() if n != "default"} raise ValueError(_format_unknown_presets_error(unknown, display)) + # Typed selectors (physics=/renderer=) must have landed on a cfg of their type + _validate_typed_presets(requested_targets, typed_hits) + cfgs = {"env": env_cfg, "agent": agent_cfg} for key, val, arg in override_items: if key in consumed_explicit: diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/preset_cli.py b/source/isaaclab_tasks/isaaclab_tasks/utils/preset_cli.py index 439e67955fea..312cb37a43f5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/preset_cli.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/preset_cli.py @@ -11,20 +11,13 @@ * ``renderer=NAME`` -- typed selector for ``RendererCfg`` variants. * ``presets=NAME[,NAME,...]`` -- broadcast applied to every matching ``PresetCfg``. -Two responsibilities, split across two functions: - -* :func:`setup_preset_cli` -- register the preset-selection help description on - the parser and run ``parse_known_args``. Returns the raw pre-fold remainder. -* :func:`fold_preset_tokens` -- rewrite typed selectors and any free-form - ``presets=...`` tokens into a single ``presets=`` token that hydra's - :func:`~isaaclab_tasks.utils.hydra.resolve_presets` consumes. The resolver, - alias rewriting, and unknown-name errors are unchanged. - -Splitting the fold out lets callers intersect the pre-fold remainder with -external sources (e.g. ``rsl_rl`` scripts' ``--external_callback`` hook, which -reads the user's unmutated ``sys.argv`` and returns pre-fold tokens) in the -same vocabulary. The fold runs exactly once, at the caller's final -``sys.argv`` assignment. +:func:`setup_preset_cli` registers the preset-selection help description on the +parser and runs ``parse_known_args``, returning the verbatim remainder. The +tokens above are passed through unchanged; hydra's +:func:`~isaaclab_tasks.utils.hydra.register_task` parses them directly (applying +the names as presets and enforcing that ``physics=``/``renderer=`` resolve +against a config of that type). Callers simply assign the remainder to +``sys.argv``; no rewriting step is needed. No argparse arguments are registered for the typed selectors -- discoverability lives in the ``argument_group`` description, so the parsed Namespace gains no @@ -37,16 +30,17 @@ # ... script-specific args ... add_launcher_args(parser) args_cli, remaining = setup_preset_cli(parser) - sys.argv = [sys.argv[0]] + fold_preset_tokens(remaining) + sys.argv = [sys.argv[0]] + remaining -Scripts that need to intersect the remainder with external-callback output do -the intersection first (both sides pre-fold, vocabulary matches), then fold:: +Scripts that intersect the remainder with external-callback output (e.g. +``rsl_rl`` scripts' ``--external_callback`` hook) do the intersection on the +remainder before assigning ``sys.argv`` -- both sides share the same token +vocabulary:: args_cli, remaining = setup_preset_cli(parser) if args_cli.external_callback: - cb_remainder = external_callback_function() - remaining = list_intersection(remaining, cb_remainder) - sys.argv = [sys.argv[0]] + fold_preset_tokens(remaining) + remaining = list_intersection(remaining, external_callback_function()) + sys.argv = [sys.argv[0]] + remaining ``setup_preset_cli`` does NOT add AppLauncher flags itself -- callers add them explicitly via :func:`isaaclab.app.add_launcher_args` before calling. @@ -73,18 +67,14 @@ def setup_preset_cli( registered on ``parser`` -- otherwise those unknown tokens land in ``parse_known_args``'s remainder. - Does NOT fold typed selectors. The returned remainder still contains the - user-typed ``physics=`` / ``renderer=`` / ``presets=`` tokens verbatim, - alongside any Hydra path overrides and any unknown argparse flags. Call - :func:`fold_preset_tokens` on the remainder before assigning ``sys.argv``; - keeping parse and fold separate lets callers run other filters (notably - ``rsl_rl``'s ``--external_callback`` intersection) on the pre-fold list, - where vocabularies match. + The returned remainder contains the user-typed ``physics=`` / ``renderer=`` + / ``presets=`` tokens verbatim, alongside any Hydra path overrides and any + unknown argparse flags, ready to assign to ``sys.argv`` for hydra to parse. Does not mutate ``sys.argv``; the caller assigns - ``sys.argv = [sys.argv[0]] + fold_preset_tokens(remaining)`` when ready, so - any argv-aware logic that re-reads ``sys.argv`` (e.g. an external callback) - runs against the user's original command line. + ``sys.argv = [sys.argv[0]] + remaining`` when ready, so any argv-aware logic + that re-reads ``sys.argv`` (e.g. an external callback) runs against the + user's original command line first. Args: parser: Caller's argument parser. An ``argument_group`` is attached @@ -99,8 +89,8 @@ def setup_preset_cli( Returns: ``(args, remaining)`` where ``remaining`` is the verbatim output of - ``parser.parse_known_args(argv)``. Apply :func:`fold_preset_tokens` - to ``remaining`` before handing it to Hydra. + ``parser.parse_known_args(argv)``, ready to hand to Hydra via + ``sys.argv``. """ # --help short-circuits parsing, so help text that depends on --task has to # find it before argparse runs. Gate the env_cfg load on --help to keep @@ -125,58 +115,6 @@ def setup_preset_cli( return parser.parse_known_args(argv) -def fold_preset_tokens(tokens: list[str]) -> list[str]: - """Fold preset selector tokens into a single ``presets=`` token. - - Recognises ``physics=NAME`` / ``renderer=NAME`` / ``presets=NAME[,NAME,...]`` - in *tokens* (exact key match; dotted keys like ``env.sim.physics=NAME`` are - path-targeted overrides and pass through unchanged). All recognised names - are deduped in first-occurrence order and emitted as a leading - ``presets=`` token; every other token in *tokens* is appended in its - original position. - - Call this on the remainder returned by :func:`setup_preset_cli` before - assigning ``sys.argv``. Scripts that intersect the remainder with - callback-returned tokens (e.g. ``rsl_rl/{train,play}.py``'s - ``--external_callback`` flow) must do the intersection *first* (both sides - pre-fold) and then call this function. - - Args: - tokens: Pre-fold token list (typically the second element of the - tuple returned by :func:`setup_preset_cli`). - - Returns: - A new list with selector tokens folded into one leading - ``presets=`` token if any were present; otherwise the input list - is returned unchanged. - """ - typed_labels = {t.value for t in PresetTarget if t.base_classes} - names: list[str] = [] - kept: list[str] = [] - for token in tokens: - if "=" not in token: - kept.append(token) - continue - key, val = token.split("=", 1) - if key in typed_labels: - # Typed selector value is a single name; commas are reserved for ``presets=`` broadcast. - stripped = val.strip() - if stripped: - names.append(stripped) - elif key == PresetTarget.DOMAIN.value: - names.extend(name.strip() for name in val.split(",") if name.strip()) - else: - kept.append(token) - - if not names: - return list(kept) - - # Dedupe, preserve first-occurrence order. - seen: set[str] = set() - deduped = [name for name in names if not (name in seen or seen.add(name))] - return [f"presets={','.join(deduped)}", *kept] - - # ============================================================================ # Public preset enumeration (for tooling, e.g. list_envs) # ============================================================================ diff --git a/source/isaaclab_tasks/test/core/test_hydra.py b/source/isaaclab_tasks/test/core/test_hydra.py index cec138d45a5b..b6afde637e84 100644 --- a/source/isaaclab_tasks/test/core/test_hydra.py +++ b/source/isaaclab_tasks/test/core/test_hydra.py @@ -1423,3 +1423,91 @@ class RootCyclicA(PresetCfg): with pytest.raises(ValueError, match="[Cc]ycl"): resolve_presets(RootCyclicA()) + + +# ============================================================================= +# Tests: typed-selector validation (physics=/renderer= must hit their type) +# ============================================================================= + +from isaaclab.physics import PhysicsCfg as _RealPhysicsCfg # noqa: E402 + +from isaaclab_tasks.utils.preset_target import PresetTarget # noqa: E402 + + +@configclass +class _NewtonPhysicsCfg(_RealPhysicsCfg): + """Minimal real ``PhysicsCfg`` subclass so isinstance bucketing routes to PHYSICS.""" + + dt: float = 0.002 + + +@configclass +class _PhysxPhysicsCfg(_RealPhysicsCfg): + dt: float = 0.005 + + +def test_validate_typed_presets_passes_when_selector_hits_its_type(): + """``physics=newton_mjwarp`` that landed on a PhysicsCfg does not raise.""" + hydra_mod._validate_typed_presets( + {PresetTarget.PHYSICS: {"newton_mjwarp"}}, + typed_hits={"newton_mjwarp": {PresetTarget.PHYSICS}}, + ) + + +def test_validate_typed_presets_raises_when_selector_misses_its_type(): + """``physics=newton_mjwarp`` that never landed on a PhysicsCfg must raise.""" + with pytest.raises(ValueError, match="physics=newton_mjwarp"): + hydra_mod._validate_typed_presets({PresetTarget.PHYSICS: {"newton_mjwarp"}}, typed_hits={}) + + +def test_validate_typed_presets_ignores_broadcast_presets(): + """A plain ``presets=`` broadcast is never in ``requested``, so it is trusted.""" + # No typed selectors requested -> nothing to validate, even with no hits. + hydra_mod._validate_typed_presets({}, typed_hits={}) + + +def test_resolve_active_presets_records_physics_hit_for_selector(): + """End-to-end: selecting a name that resolves to a real PhysicsCfg records a PHYSICS hit.""" + + @configclass + class PhysicsPresetCfg(PresetCfg): + default: _PhysxPhysicsCfg = _PhysxPhysicsCfg() + newton_mjwarp: _NewtonPhysicsCfg = _NewtonPhysicsCfg() + + @configclass + class EnvWithPhysicsCfg: + physics: PhysicsPresetCfg = PhysicsPresetCfg() + + typed_hits: dict[str, set[PresetTarget]] = {} + hydra_mod._resolve_active_presets( + EnvWithPhysicsCfg(), ["newton_mjwarp"], {}, root_path="env", typed_hits=typed_hits + ) + assert PresetTarget.PHYSICS in typed_hits.get("newton_mjwarp", set()) + # physics=newton_mjwarp therefore validates. + hydra_mod._validate_typed_presets({PresetTarget.PHYSICS: {"newton_mjwarp"}}, typed_hits) + + +def test_resolve_active_presets_no_physics_hit_for_scalar_preset(): + """A name resolving only to a scalar records no typed hit, so a physics= selector raises.""" + + @configclass + class EnvWithScalarOnlyCfg: + # ``newton_mjwarp`` here only tunes a scalar -- no PhysicsCfg involved. + armature: PresetCfg = preset(default=0.0, newton_mjwarp=0.01) + + consumed: set[str] = set() + typed_hits: dict[str, set[PresetTarget]] = {} + hydra_mod._resolve_active_presets( + EnvWithScalarOnlyCfg(), + ["newton_mjwarp"], + {}, + root_path="env", + consumed_selected=consumed, + typed_hits=typed_hits, + ) + assert "newton_mjwarp" in consumed and PresetTarget.PHYSICS not in typed_hits.get("newton_mjwarp", set()) + # presets=newton_mjwarp (broadcast) is trusted: no entry in ``requested`` -> no error. + hydra_mod._validate_typed_presets({}, typed_hits) + # physics=newton_mjwarp (typed selector) must error. + with pytest.raises(ValueError, match="physics=newton_mjwarp"): + hydra_mod._validate_typed_presets({PresetTarget.PHYSICS: {"newton_mjwarp"}}, typed_hits) diff --git a/source/isaaclab_tasks/test/core/test_preset_cli.py b/source/isaaclab_tasks/test/core/test_preset_cli.py index 7687425cd9f3..355a5f1da209 100644 --- a/source/isaaclab_tasks/test/core/test_preset_cli.py +++ b/source/isaaclab_tasks/test/core/test_preset_cli.py @@ -3,23 +3,15 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Tests for the typed-preset CLI translator. +"""Tests for the typed-preset CLI front-end. -Two functions cover the translator: +:func:`setup_preset_cli` registers the preset-selection help description and +runs ``parse_known_args``, returning the verbatim remainder. The +``physics=``/``renderer=``/``presets=`` tokens are passed through unchanged; +Hydra's :func:`~isaaclab_tasks.utils.hydra.register_task` parses them directly. -* :func:`setup_preset_cli` -- register help description and parse argv. - Returns the raw pre-fold remainder; no folding happens inside. -* :func:`fold_preset_tokens` -- fold typed selectors (``physics=``, - ``renderer=``) and free-form ``presets=`` into a single - ``presets=`` token consumed by Hydra's resolver. - -Splitting parse from fold lets callers (notably ``rsl_rl/{train,play}.py``) -intersect the pre-fold remainder with an ``--external_callback`` return list -in matching vocabulary before folding once at the end. Tests below cover both -functions individually plus the bug-fix scenario they were split for. - -Name validation, alias rewriting, and resolution all live in -:mod:`isaaclab_tasks.utils.hydra` and have their own tests in +Name validation, alias rewriting, typed-selector enforcement, and resolution +all live in :mod:`isaaclab_tasks.utils.hydra` and have their own tests in ``test_hydra.py``; this file does not re-cover them. """ @@ -84,9 +76,9 @@ def test_setup_preset_cli_returns_remainder_only(monkeypatch): def test_setup_preset_cli_passes_typed_tokens_verbatim(monkeypatch): - """``setup_preset_cli`` no longer folds; preset tokens come back in - their original ``physics=`` / ``renderer=`` / ``presets=`` form so callers - can intersect with callback returns in matching vocabulary before folding.""" + """Preset tokens come back in their original ``physics=`` / ``renderer=`` / + ``presets=`` form so hydra can parse them directly and callers can intersect + with callback returns in matching vocabulary.""" monkeypatch.setattr( "sys.argv", [ @@ -113,15 +105,15 @@ def test_setup_preset_cli_does_not_mutate_sys_argv(monkeypatch): """``setup_preset_cli`` must not mutate ``sys.argv`` -- mutation is the caller's responsibility. Locks the contract that ``rsl_rl/{train,play}.py`` rely on so an ``--external_callback`` hook invoked after ``setup_preset_cli`` - can still read the user's original command line and return pre-fold tokens - that the caller intersects against the pre-fold remainder.""" + can still read the user's original command line and return tokens that the + caller intersects against the remainder.""" original = ["train.py", "--task=Foo-v0", "physics=newton_mjwarp", "env.sim.dt=0.001"] monkeypatch.setattr("sys.argv", original) from isaaclab_tasks.utils.preset_cli import setup_preset_cli _, remaining = setup_preset_cli(_make_parser()) assert sys.argv == original - # Remainder is pre-fold (typed selector unchanged). + # Remainder carries the typed selector unchanged. assert remaining == ["physics=newton_mjwarp", "env.sim.dt=0.001"] @@ -177,180 +169,26 @@ def test_setup_preset_cli_does_not_leak_into_app_launcher_sim_app_intersection(m # --------------------------------------------------------------------------- -# fold_preset_tokens: typed + broadcast tokens fold into one presets= token -# --------------------------------------------------------------------------- - - -def test_fold_returns_empty_input_unchanged(): - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens([]) == [] - - -def test_fold_no_preset_tokens_returns_input_unchanged(): - """Path-targeted overrides and unknown ``--flag``s pass through verbatim.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["env.sim.dt=0.001"]) == ["env.sim.dt=0.001"] - assert fold_preset_tokens(["--my_flag=42", "agent.lr=3e-4"]) == ["--my_flag=42", "agent.lr=3e-4"] - - -def test_fold_physics_token_to_presets_token(): - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["physics=newton_mjwarp", "env.sim.dt=0.001"]) == [ - "presets=newton_mjwarp", - "env.sim.dt=0.001", - ] - - -def test_fold_three_selectors_merge_into_one_token(): - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens( - [ - "physics=newton_mjwarp", - "renderer=newton_renderer", - "presets=albedo,depth", - ] - ) == ["presets=newton_mjwarp,newton_renderer,albedo,depth"] - - -def test_fold_dedupes_repeated_names(): - """A name appearing in both a typed selector and the broadcast list - survives once in the folded token.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["physics=newton_mjwarp", "presets=newton_mjwarp,albedo"]) == [ - "presets=newton_mjwarp,albedo" - ] - - -def test_fold_path_targeted_overrides_pass_through(): - """``env.sim.physics=NAME`` is a Hydra path-targeted override (dotted key) - not a typed preset selector (bare ``physics``); it must pass through the - fold untouched and reach the resolver in its original form.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["physics=newton_mjwarp", "env.sim.physics=newton_mjwarp", "env.lr=3e-4"]) == [ - "presets=newton_mjwarp", - "env.sim.physics=newton_mjwarp", - "env.lr=3e-4", - ] - - -def test_fold_unknown_argparse_flag_passes_through(): - """Anything starting with ``--`` is not a preset token; the fold leaves - callback-owned flags in place so the caller's intersection step can drop - them via the callback's claim.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["--my_callback_flag=42", "physics=newton_mjwarp"]) == [ - "presets=newton_mjwarp", - "--my_callback_flag=42", - ] - - -def test_fold_unknown_name_passes_through_silently(capsys): - """A name unknown to the registry is passed through verbatim with no - warning. The resolver has the loaded task's full vocabulary and produces - the rich error at resolve time if the name truly doesn't exist.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["physics=newton_mujoco"]) == ["presets=newton_mujoco"] - assert capsys.readouterr().err == "" - - -def test_fold_custom_task_preset_via_broadcast_passes_through(capsys): - """A task-local custom preset name (e.g. Dexsuite's ``cube``) is accepted - via the broadcast selector with no fuss -- the registry is a hint, not a gate.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["presets=cube,peg_insert_4mm,mayank_solver"]) == [ - "presets=cube,peg_insert_4mm,mayank_solver" - ] - assert capsys.readouterr().err == "" - - -def test_fold_keeps_relative_order_of_non_preset_tokens(): - """Non-preset tokens retain their relative order; the folded - ``presets=`` token is prepended.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["env.a=1", "physics=newton_mjwarp", "env.b=2", "env.c=3"]) == [ - "presets=newton_mjwarp", - "env.a=1", - "env.b=2", - "env.c=3", - ] - - -def test_fold_drops_empty_typed_value(): - """An empty typed-selector value (``physics=``) is skipped, not folded - as an empty name.""" - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - assert fold_preset_tokens(["physics=", "env.sim.dt=0.001"]) == ["env.sim.dt=0.001"] - - -# --------------------------------------------------------------------------- -# Bug fix regression: intersection-then-fold preserves typed preset selections +# External-callback intersection: typed selectors survive on the raw remainder # -# Reproduces the rsl_rl/{train,play}.py + --external_callback failure mode -# (PR #5587 review): a callback that reads the user's pre-fold sys.argv and -# returns pre-fold tokens must be intersected before folding so vocabularies -# match. Folding first would put ``presets=NAME`` on one side and -# ``physics=NAME`` on the other, dropping the preset by string mismatch. +# rsl_rl/{train,play}.py intersect the parsed remainder with an +# ``--external_callback`` return list before assigning ``sys.argv``. Because +# nothing rewrites the tokens, both sides share the same vocabulary and a typed +# selector present in both survives the intersection unchanged. # --------------------------------------------------------------------------- -def test_intersection_then_fold_preserves_typed_selection(): - """The bug-fix order: list_intersection on pre-fold tokens, then fold once. - - Models the rsl_rl callback path. With this order, a typed selector - (``physics=newton_mjwarp``) appearing in both the main remainder and the - callback's pre-fold return survives the intersection and folds correctly. - """ +def test_intersection_preserves_typed_selection(): + """A typed selector present in both the remainder and the callback return + survives ``list_intersection`` verbatim; a callback-owned flag is dropped.""" from isaaclab.utils.string import list_intersection - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - main_remainder_pre_fold = [ - "physics=newton_mjwarp", - "--my_callback_flag=42", # main parser doesn't know this; callback owns it - "env.lr=3e-4", - ] - # Callback reads (untouched) sys.argv, consumes its --my_callback_flag, returns the rest. - callback_remainder_pre_fold = ["physics=newton_mjwarp", "env.lr=3e-4"] - - intersected = list_intersection(main_remainder_pre_fold, callback_remainder_pre_fold) - folded = fold_preset_tokens(intersected) - - # Preset selection survives; callback-owned flag is correctly dropped. - assert folded == ["presets=newton_mjwarp", "env.lr=3e-4"] - - -def test_fold_then_intersection_would_lose_typed_selection(): - """Document the wrong order. If the caller folded first and intersected - second, the post-fold ``presets=newton_mjwarp`` would not match the - callback's pre-fold ``physics=newton_mjwarp`` and the preset would be - silently dropped. This test pins the bug shape so a future caller doesn't - accidentally re-introduce it. - """ - from isaaclab.utils.string import list_intersection - - from isaaclab_tasks.utils.preset_cli import fold_preset_tokens - - main_remainder_pre_fold = ["physics=newton_mjwarp", "--my_callback_flag=42", "env.lr=3e-4"] - callback_remainder_pre_fold = ["physics=newton_mjwarp", "env.lr=3e-4"] + main_remainder = ["physics=newton_mjwarp", "--my_callback_flag=42", "env.lr=3e-4"] + callback_remainder = ["physics=newton_mjwarp", "env.lr=3e-4"] - # Wrong order: fold main first, then intersect against pre-fold callback. - folded_first = fold_preset_tokens(main_remainder_pre_fold) - intersected = list_intersection(folded_first, callback_remainder_pre_fold) + intersected = list_intersection(main_remainder, callback_remainder) - # Preset is gone -- this is exactly the bug to avoid in rsl_rl scripts. - assert intersected == ["env.lr=3e-4"] - assert "presets=newton_mjwarp" not in intersected + assert intersected == ["physics=newton_mjwarp", "env.lr=3e-4"] # --------------------------------------------------------------------------- From c01bbc0f5a3684dbb61ba178e3210e618292da2f Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Sat, 6 Jun 2026 06:14:05 +0000 Subject: [PATCH 05/40] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 6.3.1 → 6.4.0 - isaaclab_contrib: 0.4.3 → 0.4.4 - isaaclab_newton: 0.15.1 → 0.15.2 - isaaclab_ov: 0.4.2 → 0.4.3 - isaaclab_physx: 1.1.3 → 1.1.4 - isaaclab_tasks: 2.0.3 → 3.0.0 - isaaclab_visualizers: 0.1.2 → 0.1.3 --- .../clarify-single-video-stream.rst | 6 -- .../clarify-visualizer-camera-sensor-mode.rst | 6 -- ...volk-fix-manager-based-env-close-leaks.rst | 8 -- ...fix-scene-data-articulation-transforms.rst | 6 -- ...nh-fix-cube-base-env-replicate-physics.rst | 5 -- .../jmart-framestack-perf.minor.rst | 25 ------- ...repte-tiled-camera-visualizer-tutorial.rst | 5 -- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 52 +++++++++++++ source/isaaclab/pyproject.toml | 2 +- ...ix-check-instanceable-physics-context.skip | 0 .../mingxue-fix_rlinf_on_windows11_spark.rst | 5 -- source/isaaclab_contrib/config/extension.toml | 2 +- source/isaaclab_contrib/docs/CHANGELOG.rst | 10 +++ source/isaaclab_contrib/pyproject.toml | 2 +- .../expose-newton-contact-buffer.rst | 5 -- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 10 +++ source/isaaclab_newton/pyproject.toml | 2 +- .../pbarejko-ovrtx-updated-documentation.rst | 6 -- source/isaaclab_ov/config/extension.toml | 2 +- source/isaaclab_ov/docs/CHANGELOG.rst | 11 +++ source/isaaclab_ov/pyproject.toml | 2 +- ...ix-check-instanceable-physics-context.skip | 0 ...repte-tiled-camera-visualizer-tutorial.rst | 5 -- .../reduce-ant-joint-wrench-warnings.rst | 6 -- source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 17 +++++ source/isaaclab_physx/pyproject.toml | 2 +- .../jichuanh-fix-template-generator.skip | 0 .../mhaiderbhai-merge-locomotion-tasks.skip | 1 - .../fix-hydra-typed-preset-validation.rst | 21 ------ .../changelog.d/jmart-framestack-perf.rst | 8 -- ...aiderbhai-merge-locomotion-tasks.major.rst | 46 ------------ source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 74 +++++++++++++++++++ source/isaaclab_tasks/pyproject.toml | 2 +- .../fix-newton-contact-visualization.rst | 6 -- .../fix-newton-hud-imgui-dependency.rst | 15 ---- ...repte-tiled-camera-visualizer-tutorial.rst | 5 -- .../config/extension.toml | 2 +- .../isaaclab_visualizers/docs/CHANGELOG.rst | 29 ++++++++ source/isaaclab_visualizers/pyproject.toml | 2 +- 43 files changed, 217 insertions(+), 204 deletions(-) delete mode 100644 source/isaaclab/changelog.d/clarify-single-video-stream.rst delete mode 100644 source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst delete mode 100644 source/isaaclab/changelog.d/cvolk-fix-manager-based-env-close-leaks.rst delete mode 100644 source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst delete mode 100644 source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst delete mode 100644 source/isaaclab/changelog.d/jmart-framestack-perf.minor.rst delete mode 100644 source/isaaclab/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst delete mode 100644 source/isaaclab_contrib/changelog.d/antoiner-fix-check-instanceable-physics-context.skip delete mode 100644 source/isaaclab_contrib/changelog.d/mingxue-fix_rlinf_on_windows11_spark.rst delete mode 100644 source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst delete mode 100644 source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst delete mode 100644 source/isaaclab_physx/changelog.d/antoiner-fix-check-instanceable-physics-context.skip delete mode 100644 source/isaaclab_physx/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst delete mode 100644 source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst delete mode 100644 source/isaaclab_rl/changelog.d/jichuanh-fix-template-generator.skip delete mode 100644 source/isaaclab_rl/changelog.d/mhaiderbhai-merge-locomotion-tasks.skip delete mode 100644 source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst delete mode 100644 source/isaaclab_tasks/changelog.d/jmart-framestack-perf.rst delete mode 100644 source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-locomotion-tasks.major.rst delete mode 100644 source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst delete mode 100644 source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst delete mode 100644 source/isaaclab_visualizers/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst diff --git a/source/isaaclab/changelog.d/clarify-single-video-stream.rst b/source/isaaclab/changelog.d/clarify-single-video-stream.rst deleted file mode 100644 index 39e5bacdc191..000000000000 --- a/source/isaaclab/changelog.d/clarify-single-video-stream.rst +++ /dev/null @@ -1,6 +0,0 @@ -Changed -^^^^^^^ - -* Clarified ``--video`` behavior when multiple video-capable visualizers are active: - Gymnasium video recording captures one ``env.render()`` stream, with Kit taking - priority over Newton. diff --git a/source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst b/source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst deleted file mode 100644 index cb6f9c0081f7..000000000000 --- a/source/isaaclab/changelog.d/clarify-visualizer-camera-sensor-mode.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Improved visualizer tiled-camera errors when ``tiled_cam_prim_path`` is set but - the scene has no Isaac Lab ``Camera`` sensors, and clarified the camera-mode - documentation for Cartpole camera tasks. diff --git a/source/isaaclab/changelog.d/cvolk-fix-manager-based-env-close-leaks.rst b/source/isaaclab/changelog.d/cvolk-fix-manager-based-env-close-leaks.rst deleted file mode 100644 index 188a9bb922f0..000000000000 --- a/source/isaaclab/changelog.d/cvolk-fix-manager-based-env-close-leaks.rst +++ /dev/null @@ -1,8 +0,0 @@ -Fixed -^^^^^ - -* Fixed a memory leak in :meth:`~isaaclab.envs.ManagerBasedEnv.close`, - :meth:`~isaaclab.envs.DirectRLEnv.close` and :meth:`~isaaclab.envs.DirectMARLEnv.close` - where the cached observation buffers and the :class:`gym.spaces` observation/action - spaces were never released, causing host and GPU memory to accumulate on each - environment construct/teardown cycle. diff --git a/source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst b/source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst deleted file mode 100644 index 14be85dbc997..000000000000 --- a/source/isaaclab/changelog.d/fix-scene-data-articulation-transforms.rst +++ /dev/null @@ -1,6 +0,0 @@ -Added -^^^^^ - -* Added a scene-data backend hook for active ``InteractiveScene`` access so - backends can source scene-owned entity transforms without relying on global - rigid-body views, and visualizers can discover scene-owned contact sensors. diff --git a/source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst b/source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst deleted file mode 100644 index c98b503c6eca..000000000000 --- a/source/isaaclab/changelog.d/jichuanh-fix-cube-base-env-replicate-physics.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed the ``create_cube_base_env`` tutorial crashing at startup with a ``RuntimeError`` - because its prestartup USD-level randomization terms ran while scene replication was enabled. diff --git a/source/isaaclab/changelog.d/jmart-framestack-perf.minor.rst b/source/isaaclab/changelog.d/jmart-framestack-perf.minor.rst deleted file mode 100644 index 3adadd35f4d2..000000000000 --- a/source/isaaclab/changelog.d/jmart-framestack-perf.minor.rst +++ /dev/null @@ -1,25 +0,0 @@ -Added -^^^^^ - -* Added :paramref:`~isaaclab.utils.buffers.CircularBuffer.stack_dim` constructor argument - and :attr:`~isaaclab.utils.buffers.CircularBuffer.stacked` property: when ``stack_dim`` is - set, the internal storage is rearranged so ``stacked`` returns the ``K`` frames merged - along the chosen dim as a free contiguous view. -* Added :mod:`isaaclab.utils.images` with :func:`~isaaclab.utils.images.normalize_camera_image` - and the ``is_rgb_like`` / ``is_depth_like`` / ``is_normals_like`` predicates, shared - between the DirectRLEnv and ManagerBasedEnv camera observation paths. -* Added :func:`isaaclab.utils.warp.ops.normalize_image_uint8`, a fused Warp-kernel - implementation of ``(uint8 / 255) - per-image-channel mean`` for RGB-like camera - observations. Supports both ``(B, H, W, C)`` and ``(B, C, H, W)`` inputs via a - ``channel_dim`` argument (``-1`` / ``3`` for BHWC, ``-3`` / ``1`` for BCHW); the - argument is also forwarded by :func:`~isaaclab.utils.images.normalize_camera_image`. -* Added a ``clone`` kwarg to :func:`isaaclab.envs.mdp.observations.image`; callers that - immediately copy the result into their own storage (e.g. a frame-stack buffer) can pass - ``clone=False`` to skip the redundant allocation. - -Changed -^^^^^^^ - -* Changed :class:`~isaaclab.envs.mdp.observations.stacked_image` to use the new ``stack_dim`` - ``CircularBuffer`` layout and defer normalization past the frame-stack buffer for RGB-like - data types, eliminating a per-frame float32 upcast and large transpose. diff --git a/source/isaaclab/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst b/source/isaaclab/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst deleted file mode 100644 index cdcfeb741c8e..000000000000 --- a/source/isaaclab/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst +++ /dev/null @@ -1,5 +0,0 @@ -Changed -^^^^^^^ - -* Updated the visualizer tiled camera tutorial to show generated Kit cameras and - existing Newton robot-mounted camera streams with matching documentation figures. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 8166c2a20031..2fd1fa73394e 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "6.3.1" +version = "6.4.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 1237e7a104a7..587fb0c52314 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,58 @@ Changelog --------- +6.4.0 (2026-06-06) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :paramref:`~isaaclab.utils.buffers.CircularBuffer.stack_dim` constructor argument + and :attr:`~isaaclab.utils.buffers.CircularBuffer.stacked` property: when ``stack_dim`` is + set, the internal storage is rearranged so ``stacked`` returns the ``K`` frames merged + along the chosen dim as a free contiguous view. +* Added :mod:`isaaclab.utils.images` with :func:`~isaaclab.utils.images.normalize_camera_image` + and the ``is_rgb_like`` / ``is_depth_like`` / ``is_normals_like`` predicates, shared + between the DirectRLEnv and ManagerBasedEnv camera observation paths. +* Added :func:`isaaclab.utils.warp.ops.normalize_image_uint8`, a fused Warp-kernel + implementation of ``(uint8 / 255) - per-image-channel mean`` for RGB-like camera + observations. Supports both ``(B, H, W, C)`` and ``(B, C, H, W)`` inputs via a + ``channel_dim`` argument (``-1`` / ``3`` for BHWC, ``-3`` / ``1`` for BCHW); the + argument is also forwarded by :func:`~isaaclab.utils.images.normalize_camera_image`. +* Added a ``clone`` kwarg to :func:`isaaclab.envs.mdp.observations.image`; callers that + immediately copy the result into their own storage (e.g. a frame-stack buffer) can pass + ``clone=False`` to skip the redundant allocation. +* Added a scene-data backend hook for active ``InteractiveScene`` access so + backends can source scene-owned entity transforms without relying on global + rigid-body views, and visualizers can discover scene-owned contact sensors. + +Changed +^^^^^^^ + +* Updated the visualizer tiled camera tutorial to show generated Kit cameras and + existing Newton robot-mounted camera streams with matching documentation figures. +* Changed :class:`~isaaclab.envs.mdp.observations.stacked_image` to use the new ``stack_dim`` + ``CircularBuffer`` layout and defer normalization past the frame-stack buffer for RGB-like + data types, eliminating a per-frame float32 upcast and large transpose. +* Clarified ``--video`` behavior when multiple video-capable visualizers are active: + Gymnasium video recording captures one ``env.render()`` stream, with Kit taking + priority over Newton. + +Fixed +^^^^^ + +* Fixed a memory leak in :meth:`~isaaclab.envs.ManagerBasedEnv.close`, + :meth:`~isaaclab.envs.DirectRLEnv.close` and :meth:`~isaaclab.envs.DirectMARLEnv.close` + where the cached observation buffers and the :class:`gym.spaces` observation/action + spaces were never released, causing host and GPU memory to accumulate on each + environment construct/teardown cycle. +* Fixed the ``create_cube_base_env`` tutorial crashing at startup with a ``RuntimeError`` + because its prestartup USD-level randomization terms ran while scene replication was enabled. +* Improved visualizer tiled-camera errors when ``tiled_cam_prim_path`` is set but + the scene has no Isaac Lab ``Camera`` sensors, and clarified the camera-mode + documentation for Cartpole camera tasks. + + 6.3.1 (2026-06-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/pyproject.toml b/source/isaaclab/pyproject.toml index b3f6f302d0f4..2dd4ebcedd62 100644 --- a/source/isaaclab/pyproject.toml +++ b/source/isaaclab/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab" -version = "6.3.1" +version = "6.4.0" description = "Extension providing main framework interfaces and abstractions for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_contrib/changelog.d/antoiner-fix-check-instanceable-physics-context.skip b/source/isaaclab_contrib/changelog.d/antoiner-fix-check-instanceable-physics-context.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_contrib/changelog.d/mingxue-fix_rlinf_on_windows11_spark.rst b/source/isaaclab_contrib/changelog.d/mingxue-fix_rlinf_on_windows11_spark.rst deleted file mode 100644 index 9472ff3864c5..000000000000 --- a/source/isaaclab_contrib/changelog.d/mingxue-fix_rlinf_on_windows11_spark.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed RLinf optional dependency installation on DGX Spark and aarch64 by - replacing ``decord`` with ``decord2`` in the ``rlinf`` extras. diff --git a/source/isaaclab_contrib/config/extension.toml b/source/isaaclab_contrib/config/extension.toml index 02f6bf9bcb63..644f71728b00 100644 --- a/source/isaaclab_contrib/config/extension.toml +++ b/source/isaaclab_contrib/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.4.3" +version = "0.4.4" # Description title = "Isaac Lab External Contributions" diff --git a/source/isaaclab_contrib/docs/CHANGELOG.rst b/source/isaaclab_contrib/docs/CHANGELOG.rst index 09632ccb9a8d..9bb4124c7b3e 100644 --- a/source/isaaclab_contrib/docs/CHANGELOG.rst +++ b/source/isaaclab_contrib/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.4.4 (2026-06-06) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed RLinf optional dependency installation on DGX Spark and aarch64 by + replacing ``decord`` with ``decord2`` in the ``rlinf`` extras. + + 0.4.3 (2026-06-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_contrib/pyproject.toml b/source/isaaclab_contrib/pyproject.toml index 60106c6be93f..e8f06d9a9018 100644 --- a/source/isaaclab_contrib/pyproject.toml +++ b/source/isaaclab_contrib/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_contrib" -version = "0.4.3" +version = "0.4.4" description = "An extension used to stage and integrate externally contributed features and implementations." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst b/source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst deleted file mode 100644 index 178e170378b7..000000000000 --- a/source/isaaclab_newton/changelog.d/expose-newton-contact-buffer.rst +++ /dev/null @@ -1,5 +0,0 @@ -Added -^^^^^ - -* Added a ``NewtonManager.get_contacts()`` accessor so visualizers can render - Newton contact buffers without reaching into manager internals. diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index ea58a478e919..a0dccd8b9942 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.15.1" +version = "0.15.2" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index 8a0b9e089ccd..a1f4c0d6b4c5 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.15.2 (2026-06-06) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added a ``NewtonManager.get_contacts()`` accessor so visualizers can render + Newton contact buffers without reaching into manager internals. + + 0.15.1 (2026-06-05) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/pyproject.toml b/source/isaaclab_newton/pyproject.toml index c15ac6edc787..5fc4f472fec0 100644 --- a/source/isaaclab_newton/pyproject.toml +++ b/source/isaaclab_newton/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_newton" -version = "0.15.1" +version = "0.15.2" description = "Extension providing IsaacLab with Newton specific abstractions." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst b/source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst deleted file mode 100644 index 47564d50edb4..000000000000 --- a/source/isaaclab_ov/changelog.d/pbarejko-ovrtx-updated-documentation.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed the OVRTX renderer to raise a clear, actionable error when the optional - ``ovrtx`` runtime wheel is not installed, pointing users to - ``./isaaclab.sh -i 'ov[ovrtx]'`` instead of a cryptic ``No module named 'ovrtx'``. diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index 687d739034da..476f0a33fd14 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -1,5 +1,5 @@ [package] -version = "0.4.2" +version = "0.4.3" title = "Omniverse renderers for IsaacLab" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." readme = "docs/README.md" diff --git a/source/isaaclab_ov/docs/CHANGELOG.rst b/source/isaaclab_ov/docs/CHANGELOG.rst index fa1e42555c15..d9caa2072081 100644 --- a/source/isaaclab_ov/docs/CHANGELOG.rst +++ b/source/isaaclab_ov/docs/CHANGELOG.rst @@ -1,6 +1,17 @@ Changelog --------- +0.4.3 (2026-06-06) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed the OVRTX renderer to raise a clear, actionable error when the optional + ``ovrtx`` runtime wheel is not installed, pointing users to + ``./isaaclab.sh -i 'ov[ovrtx]'`` instead of a cryptic ``No module named 'ovrtx'``. + + 0.4.2 (2026-06-02) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ov/pyproject.toml b/source/isaaclab_ov/pyproject.toml index ab4c0583ddbb..31a14bc0b13b 100644 --- a/source/isaaclab_ov/pyproject.toml +++ b/source/isaaclab_ov/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_ov" -version = "0.4.2" +version = "0.4.3" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_physx/changelog.d/antoiner-fix-check-instanceable-physics-context.skip b/source/isaaclab_physx/changelog.d/antoiner-fix-check-instanceable-physics-context.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_physx/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst b/source/isaaclab_physx/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst deleted file mode 100644 index 44f36605da86..000000000000 --- a/source/isaaclab_physx/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst +++ /dev/null @@ -1,5 +0,0 @@ -Changed -^^^^^^^ - -* Reduced Fabric topology rebuild logging to debug level when tiled camera - visualizer updates refresh view mappings. diff --git a/source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst b/source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst deleted file mode 100644 index ceab9cc95ca3..000000000000 --- a/source/isaaclab_physx/changelog.d/reduce-ant-joint-wrench-warnings.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed excessive PhysX tensor warnings from Ant tasks with ``JointWrenchSensor`` - by sourcing scene-data transforms for articulation links from Isaac Lab - articulation views instead of a global PhysX rigid-body view. diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index d5b11f2462b5..f23036ec0893 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.1.3" +version = "1.1.4" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index e1612e989ec0..d5797e4719ac 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,23 @@ Changelog --------- +1.1.4 (2026-06-06) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Reduced Fabric topology rebuild logging to debug level when tiled camera + visualizer updates refresh view mappings. + +Fixed +^^^^^ + +* Fixed excessive PhysX tensor warnings from Ant tasks with ``JointWrenchSensor`` + by sourcing scene-data transforms for articulation links from Isaac Lab + articulation views instead of a global PhysX rigid-body view. + + 1.1.3 (2026-06-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_physx/pyproject.toml b/source/isaaclab_physx/pyproject.toml index 1e0f0c54ce02..4641533578b7 100644 --- a/source/isaaclab_physx/pyproject.toml +++ b/source/isaaclab_physx/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_physx" -version = "1.1.3" +version = "1.1.4" description = "Extension providing IsaacLab with PhysX specific abstractions." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_rl/changelog.d/jichuanh-fix-template-generator.skip b/source/isaaclab_rl/changelog.d/jichuanh-fix-template-generator.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-locomotion-tasks.skip b/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-locomotion-tasks.skip deleted file mode 100644 index e45e584dde31..000000000000 --- a/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-locomotion-tasks.skip +++ /dev/null @@ -1 +0,0 @@ -Test-only: updated ant and humanoid task IDs in tests to match the consolidated/renamed environments. diff --git a/source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst b/source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst deleted file mode 100644 index 339a64e4575b..000000000000 --- a/source/isaaclab_tasks/changelog.d/fix-hydra-typed-preset-validation.rst +++ /dev/null @@ -1,21 +0,0 @@ -Added -^^^^^ - -* Added validation for the typed preset selectors ``physics=NAME`` and - ``renderer=NAME`` during Hydra resolution. A typed selector is now enforced - to resolve against a config of that type (a - :class:`~isaaclab.physics.PhysicsCfg` / renderer config) at least once; - selecting one on a task that only exposes the name as an unrelated preset - (e.g. a scalar or sensor variant) raises a descriptive :class:`ValueError` - instead of silently leaving the backend unchanged. The free-form - ``presets=NAME`` broadcast is trusted and not enforced. - -Changed -^^^^^^^ - -* **Breaking:** Removed ``isaaclab_tasks.utils.fold_preset_tokens``. - :func:`~isaaclab_tasks.utils.preset_cli.setup_preset_cli` now returns the - ``physics=`` / ``renderer=`` / ``presets=`` tokens verbatim, and - :func:`~isaaclab_tasks.utils.hydra.register_task` parses them directly. - Scripts assign the remainder to ``sys.argv`` unchanged (drop the - ``fold_preset_tokens(...)`` wrapper). diff --git a/source/isaaclab_tasks/changelog.d/jmart-framestack-perf.rst b/source/isaaclab_tasks/changelog.d/jmart-framestack-perf.rst deleted file mode 100644 index 85fab5760e2e..000000000000 --- a/source/isaaclab_tasks/changelog.d/jmart-framestack-perf.rst +++ /dev/null @@ -1,8 +0,0 @@ -Changed -^^^^^^^ - -* Changed :class:`~isaaclab_tasks.core.cartpole.cartpole_direct_camera_env.CartpoleCameraEnv` - to route image normalization through - :func:`isaaclab.utils.images.normalize_camera_image` and defer the normalize past the - frame-stack buffer for RGB-like data types, improving cartpole-camera frame-stacking - throughput. diff --git a/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-locomotion-tasks.major.rst b/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-locomotion-tasks.major.rst deleted file mode 100644 index 738b9a2461b6..000000000000 --- a/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-locomotion-tasks.major.rst +++ /dev/null @@ -1,46 +0,0 @@ -Changed -^^^^^^^ - -* **Breaking:** Grouped the ant and humanoid locomotion tasks under a new - :mod:`isaaclab_tasks.core.locomotion` package, each as a subpackage - (:mod:`isaaclab_tasks.core.locomotion.ant` and :mod:`isaaclab_tasks.core.locomotion.humanoid`). - The two subpackages share the direct-workflow base environment - (:mod:`isaaclab_tasks.core.locomotion.locomotion_direct_env`, previously - ``isaaclab_tasks.core.direct_locomotion.locomotion_env``) and the manager-workflow MDP terms - (:mod:`isaaclab_tasks.core.locomotion.mdp`, previously - ``isaaclab_tasks.core.manager_humanoid.mdp``). -* **Breaking:** Merged the direct-workflow and manager-based-workflow ant and humanoid task - packages into the per-task subpackages above; the former ``isaaclab_tasks.core.direct_ant``, - ``isaaclab_tasks.core.manager_ant``, ``isaaclab_tasks.core.direct_humanoid`` and - ``isaaclab_tasks.core.manager_humanoid`` packages were removed. Module files now carry a - ``_direct_`` or ``_manager_`` infix to disambiguate the two workflows. Update imports, e.g.: - - * ``from isaaclab_tasks.core.direct_ant.ant_env import AntEnv`` → - ``from isaaclab_tasks.core.locomotion.ant.ant_direct_env import AntEnv``. - * ``from isaaclab_tasks.core.manager_humanoid.humanoid_env_cfg import HumanoidEnvCfg`` → - ``from isaaclab_tasks.core.locomotion.humanoid.humanoid_manager_env_cfg import HumanoidEnvCfg``. - - The near-identical per-workflow ``rsl_rl_ppo_cfg`` modules were consolidated; each subpackage's - ``agents.rsl_rl_ppo_cfg`` now exposes a manager-based runner cfg (:class:`AntPPORunnerCfg` / - :class:`HumanoidPPORunnerCfg`) and a direct-workflow subclass (:class:`AntDirectPPORunnerCfg` / - :class:`HumanoidDirectPPORunnerCfg`). -* **Breaking:** Renamed the ant and humanoid Gym environment IDs to drop the ``-v0`` version suffix - and mark the direct-workflow tasks with an explicit ``-Direct`` suffix. The manager-based workflow - is the default and carries no workflow suffix. Update ``gym.make`` / ``--task`` calls: - - * ``Isaac-Ant-Direct-v0`` → ``Isaac-Ant-Direct``. - * ``Isaac-Ant-v0`` → ``Isaac-Ant``. - * ``Isaac-Humanoid-Direct-v0`` → ``Isaac-Humanoid-Direct``. - * ``Isaac-Humanoid-v0`` → ``Isaac-Humanoid``. -* **Breaking:** Renamed the cart double pendulum Gym environment ID to drop the ``-v0`` version - suffix. Update ``gym.make`` / ``--task`` calls: - - * ``Isaac-Cart-Double-Pendulum-Direct-v0`` → ``Isaac-Cart-Double-Pendulum-Direct``. - -Removed -^^^^^^^ - -* Removed the unused ``rew_scale_cart_pos`` field from - :class:`~isaaclab_tasks.core.cart_double_pendulum.cart_double_pendulum_env_cfg.CartDoublePendulumEnvCfg`. - It defaulted to ``0`` and was never applied to any reward term, so removing it does not change - training behavior. diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index f5586884babc..5a19dcdbbca7 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "2.0.3" +version = "3.0.0" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index ddbee6a035c5..2134ed07bd52 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,80 @@ Changelog --------- +3.0.0 (2026-06-06) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added validation for the typed preset selectors ``physics=NAME`` and + ``renderer=NAME`` during Hydra resolution. A typed selector is now enforced + to resolve against a config of that type (a + :class:`~isaaclab.physics.PhysicsCfg` / renderer config) at least once; + selecting one on a task that only exposes the name as an unrelated preset + (e.g. a scalar or sensor variant) raises a descriptive :class:`ValueError` + instead of silently leaving the backend unchanged. The free-form + ``presets=NAME`` broadcast is trusted and not enforced. + +Changed +^^^^^^^ + +* **Breaking:** Grouped the ant and humanoid locomotion tasks under a new + :mod:`isaaclab_tasks.core.locomotion` package, each as a subpackage + (:mod:`isaaclab_tasks.core.locomotion.ant` and :mod:`isaaclab_tasks.core.locomotion.humanoid`). + The two subpackages share the direct-workflow base environment + (:mod:`isaaclab_tasks.core.locomotion.locomotion_direct_env`, previously + ``isaaclab_tasks.core.direct_locomotion.locomotion_env``) and the manager-workflow MDP terms + (:mod:`isaaclab_tasks.core.locomotion.mdp`, previously + ``isaaclab_tasks.core.manager_humanoid.mdp``). +* **Breaking:** Merged the direct-workflow and manager-based-workflow ant and humanoid task + packages into the per-task subpackages above; the former ``isaaclab_tasks.core.direct_ant``, + ``isaaclab_tasks.core.manager_ant``, ``isaaclab_tasks.core.direct_humanoid`` and + ``isaaclab_tasks.core.manager_humanoid`` packages were removed. Module files now carry a + ``_direct_`` or ``_manager_`` infix to disambiguate the two workflows. Update imports, e.g.: + + * ``from isaaclab_tasks.core.direct_ant.ant_env import AntEnv`` → + ``from isaaclab_tasks.core.locomotion.ant.ant_direct_env import AntEnv``. + * ``from isaaclab_tasks.core.manager_humanoid.humanoid_env_cfg import HumanoidEnvCfg`` → + ``from isaaclab_tasks.core.locomotion.humanoid.humanoid_manager_env_cfg import HumanoidEnvCfg``. + + The near-identical per-workflow ``rsl_rl_ppo_cfg`` modules were consolidated; each subpackage's + ``agents.rsl_rl_ppo_cfg`` now exposes a manager-based runner cfg (:class:`AntPPORunnerCfg` / + :class:`HumanoidPPORunnerCfg`) and a direct-workflow subclass (:class:`AntDirectPPORunnerCfg` / + :class:`HumanoidDirectPPORunnerCfg`). +* **Breaking:** Renamed the ant and humanoid Gym environment IDs to drop the ``-v0`` version suffix + and mark the direct-workflow tasks with an explicit ``-Direct`` suffix. The manager-based workflow + is the default and carries no workflow suffix. Update ``gym.make`` / ``--task`` calls: + + * ``Isaac-Ant-Direct-v0`` → ``Isaac-Ant-Direct``. + * ``Isaac-Ant-v0`` → ``Isaac-Ant``. + * ``Isaac-Humanoid-Direct-v0`` → ``Isaac-Humanoid-Direct``. + * ``Isaac-Humanoid-v0`` → ``Isaac-Humanoid``. +* **Breaking:** Renamed the cart double pendulum Gym environment ID to drop the ``-v0`` version + suffix. Update ``gym.make`` / ``--task`` calls: + + * ``Isaac-Cart-Double-Pendulum-Direct-v0`` → ``Isaac-Cart-Double-Pendulum-Direct``. +* Changed :class:`~isaaclab_tasks.core.cartpole.cartpole_direct_camera_env.CartpoleCameraEnv` + to route image normalization through + :func:`isaaclab.utils.images.normalize_camera_image` and defer the normalize past the + frame-stack buffer for RGB-like data types, improving cartpole-camera frame-stacking + throughput. +* **Breaking:** Removed ``isaaclab_tasks.utils.fold_preset_tokens``. + :func:`~isaaclab_tasks.utils.preset_cli.setup_preset_cli` now returns the + ``physics=`` / ``renderer=`` / ``presets=`` tokens verbatim, and + :func:`~isaaclab_tasks.utils.hydra.register_task` parses them directly. + Scripts assign the remainder to ``sys.argv`` unchanged (drop the + ``fold_preset_tokens(...)`` wrapper). + +Removed +^^^^^^^ + +* Removed the unused ``rew_scale_cart_pos`` field from + :class:`~isaaclab_tasks.core.cart_double_pendulum.cart_double_pendulum_env_cfg.CartDoublePendulumEnvCfg`. + It defaulted to ``0`` and was never applied to any reward term, so removing it does not change + training behavior. + + 2.0.3 (2026-06-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/pyproject.toml b/source/isaaclab_tasks/pyproject.toml index b6b085c88b8a..1069c15136d1 100644 --- a/source/isaaclab_tasks/pyproject.toml +++ b/source/isaaclab_tasks/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_tasks" -version = "2.0.3" +version = "3.0.0" description = "Extension containing suite of environments for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst b/source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst deleted file mode 100644 index 255a3a270ceb..000000000000 --- a/source/isaaclab_visualizers/changelog.d/fix-newton-contact-visualization.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed Newton visualizer contact rendering by logging Newton contact buffers - when available and falling back to scene contact sensors for PhysX-backed - scenes. diff --git a/source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst b/source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst deleted file mode 100644 index bcbbbafcebcc..000000000000 --- a/source/isaaclab_visualizers/changelog.d/fix-newton-hud-imgui-dependency.rst +++ /dev/null @@ -1,15 +0,0 @@ -Fixed -^^^^^ - -* Fixed Newton visualizer HUD dependency checks by requiring - ``typing-extensions>=4.15.0`` for the Newton visualizer extra and failing - integration tests when Newton reports that ``imgui_bundle`` could not be - imported. Removed the legacy ``setup.py`` for ``isaaclab_visualizers`` now that - ``pyproject.toml`` carries the package metadata. - -* Fixed Rerun and Viser visualizers rendering Newton infinite ground planes too - small by expanding non-positive plane extents to the same large finite size - used by Newton GL. - -* Fixed Viser visualizer ground-grid flickering by reusing unchanged plane grid - line segments instead of removing and re-adding them every frame. diff --git a/source/isaaclab_visualizers/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst b/source/isaaclab_visualizers/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst deleted file mode 100644 index 4fa44258bd23..000000000000 --- a/source/isaaclab_visualizers/changelog.d/mtrepte-tiled-camera-visualizer-tutorial.rst +++ /dev/null @@ -1,5 +0,0 @@ -Changed -^^^^^^^ - -* Updated the visualizer tiled camera tutorial support to keep generated Kit - tiled camera views synchronized with their target robots. diff --git a/source/isaaclab_visualizers/config/extension.toml b/source/isaaclab_visualizers/config/extension.toml index 40b25868bb9b..daa19cd5ef58 100644 --- a/source/isaaclab_visualizers/config/extension.toml +++ b/source/isaaclab_visualizers/config/extension.toml @@ -1,7 +1,7 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.1.2" +version = "0.1.3" # Description category = "isaaclab" diff --git a/source/isaaclab_visualizers/docs/CHANGELOG.rst b/source/isaaclab_visualizers/docs/CHANGELOG.rst index 8e2350e6a053..346f8941b3bd 100644 --- a/source/isaaclab_visualizers/docs/CHANGELOG.rst +++ b/source/isaaclab_visualizers/docs/CHANGELOG.rst @@ -1,6 +1,35 @@ Changelog --------- +0.1.3 (2026-06-06) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Updated the visualizer tiled camera tutorial support to keep generated Kit + tiled camera views synchronized with their target robots. + +Fixed +^^^^^ + +* Fixed Newton visualizer contact rendering by logging Newton contact buffers + when available and falling back to scene contact sensors for PhysX-backed + scenes. +* Fixed Newton visualizer HUD dependency checks by requiring + ``typing-extensions>=4.15.0`` for the Newton visualizer extra and failing + integration tests when Newton reports that ``imgui_bundle`` could not be + imported. Removed the legacy ``setup.py`` for ``isaaclab_visualizers`` now that + ``pyproject.toml`` carries the package metadata. + +* Fixed Rerun and Viser visualizers rendering Newton infinite ground planes too + small by expanding non-positive plane extents to the same large finite size + used by Newton GL. + +* Fixed Viser visualizer ground-grid flickering by reusing unchanged plane grid + line segments instead of removing and re-adding them every frame. + + 0.1.2 (2026-06-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_visualizers/pyproject.toml b/source/isaaclab_visualizers/pyproject.toml index e39c6f7f943c..14cb7267b34c 100644 --- a/source/isaaclab_visualizers/pyproject.toml +++ b/source/isaaclab_visualizers/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab-visualizers" -version = "0.1.2" +version = "0.1.3" description = "Visualizer backends for Isaac Lab (Kit, Newton, Rerun, Viser)." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] From 697b180e0da877f556fd555b9e19c2638606b5ee Mon Sep 17 00:00:00 2001 From: Mustafa H <34825877+StafaH@users.noreply.github.com> Date: Sat, 6 Jun 2026 19:29:16 -0400 Subject: [PATCH 06/40] Fix docs build for CI (#6010) --- .github/workflows/docs.yaml | 22 ++++++++++++---------- docs/Makefile | 4 ++-- docs/conf.py | 1 + docs/requirements.txt | 1 + 4 files changed, 16 insertions(+), 12 deletions(-) diff --git a/.github/workflows/docs.yaml b/.github/workflows/docs.yaml index 013be3a5b126..c05212fac925 100644 --- a/.github/workflows/docs.yaml +++ b/.github/workflows/docs.yaml @@ -49,15 +49,16 @@ jobs: - name: Checkout code uses: actions/checkout@v6 - - name: Setup python - uses: actions/setup-python@v5 + - name: Set up uv + uses: astral-sh/setup-uv@v6 with: python-version: "3.12" - architecture: x64 - name: Install dev requirements - working-directory: ./docs - run: pip install -r requirements.txt + run: | + uv venv + uv pip install -r docs/requirements.txt + echo "$PWD/.venv/bin" >> "$GITHUB_PATH" - name: Build current version docs working-directory: ./docs @@ -80,15 +81,16 @@ jobs: - name: Checkout code uses: actions/checkout@v6 - - name: Setup python - uses: actions/setup-python@v5 + - name: Set up uv + uses: astral-sh/setup-uv@v6 with: python-version: "3.12" - architecture: x64 - name: Install dev requirements - working-directory: ./docs - run: pip install -r requirements.txt + run: | + uv venv + uv pip install -r docs/requirements.txt + echo "$PWD/.venv/bin" >> "$GITHUB_PATH" - name: Generate multi-version docs working-directory: ./docs diff --git a/docs/Makefile b/docs/Makefile index 0bff236671c8..58dde84885a2 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -10,10 +10,10 @@ BUILDDIR = _build .PHONY: multi-docs multi-docs: - @sphinx-multiversion "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) + @sphinx-multiversion "$(SOURCEDIR)" "$(BUILDDIR)" -j auto $(SPHINXOPTS) @cp _redirect/index.html $(BUILDDIR)/index.html .PHONY: current-docs current-docs: @rm -rf "$(BUILDDIR)/current" - @$(SPHINXBUILD) -W --keep-going "$(SOURCEDIR)" "$(BUILDDIR)/current" $(SPHINXOPTS) + @$(SPHINXBUILD) -W --keep-going -j auto "$(SOURCEDIR)" "$(BUILDDIR)/current" $(SPHINXOPTS) diff --git a/docs/conf.py b/docs/conf.py index 29663e068924..be6a4254b8d4 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -90,6 +90,7 @@ "sphinxcontrib.icon", "sphinx_copybutton", "sphinx_design", + "sphinx_paramlinks", "sphinx_tabs.tabs", # backwards compatibility for building docs on v1.0.0 "sphinx_multiversion", "isaaclab_docs", diff --git a/docs/requirements.txt b/docs/requirements.txt index 392951b0a8ee..3c42fa0fbc0c 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -7,6 +7,7 @@ autodocsumm sphinx-copybutton sphinx-icon sphinx_design +sphinx-paramlinks sphinxemoji sphinx-tabs # backwards compatibility for building docs on v1.0.0 sphinx-multiversion==0.2.4 From eacb2f454bc0a71b9c873dcd9276f8f693273d88 Mon Sep 17 00:00:00 2001 From: Mustafa H <34825877+StafaH@users.noreply.github.com> Date: Sat, 6 Jun 2026 21:35:09 -0400 Subject: [PATCH 07/40] Clean up reach tasks and rename (#6008) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Cleans up and migrates the core `reach` tasks in `isaaclab_tasks`, following the cartpole/ant/humanoid migration pattern. Also promotes the reach pose-tracking rewards into the shared `isaaclab.envs.mdp` terms. **Affected packages:** `isaaclab_tasks`, `isaaclab`. **Breaking** — see changelog fragments for migration. #### Task ID renames (Breaking) - Dropped the `-v0` suffix from all reach Gym IDs (manager-based, robot name retained): - `Isaac-Reach-Franka-v0` → `Isaac-Reach-Franka` (+ `-Play`, `-OSC`, `-OSC-Play`) - `Isaac-Reach-UR10-v0` → `Isaac-Reach-UR10` (+ `-Play`) #### Pose-tracking rewards centralized (Breaking) - Moved `position_command_error`, `position_command_error_tanh`, `orientation_command_error` to `isaaclab.envs.mdp.rewards` (alongside the existing velocity-tracking terms), with SI-unit docstrings. - Removed the `isaaclab_tasks.core.reach.mdp` package entirely. - Repointed all consumers (core reach, contrib OpenArm reach, contrib Digit loco-manip) to `import isaaclab.envs.mdp as mdp` — no task reaches into another task's package for these anymore. #### Code cleanup (no behavior change) - `position_command_error_tanh` now reuses `position_command_error` instead of duplicating the position computation. - `osc_env_cfg`: dropped redundant robot re-creation + duplicate import; mutates the parent's actuators in place. - `reach_env_cfg`: `ReachPhysicsCfg` references `default = physx` (no duplicate `PhysxCfg`); unified sim-config imports under `sim_utils`. - Standardized the Franka RSL-RL experiment name `franka_reach` → `reach_franka` (matches sibling configs + UR10). #### References updated - Tests (`test_rsl_rl_export_flow`, benchmarking `configs.yaml`), benchmark scripts, hydra docstring, and docs (`hydra`, `wrap_rl_env`, `environments`, `rl_existing_scripts`, leapp export). ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/features/hydra.rst | 6 +- docs/source/how-to/wrap_rl_env.rst | 8 +-- docs/source/overview/environments.rst | 16 ++--- .../rl_existing_scripts.rst | 44 ++++++------ .../exporting_policies_with_leapp.rst | 4 +- scripts/benchmarks/benchmark_hydra_resolve.py | 2 +- scripts/benchmarks/benchmark_lazy_export.py | 2 +- scripts/benchmarks/run_non_rl_benchmarks.sh | 2 +- scripts/benchmarks/run_training_benchmarks.sh | 2 +- ...haiderbhai-pose-tracking-rewards.minor.rst | 8 +++ .../isaaclab/isaaclab/envs/mdp/__init__.pyi | 6 ++ source/isaaclab/isaaclab/envs/mdp/rewards.py | 53 ++++++++++++++ .../mhaiderbhai-cleanup-reach-tasks.skip | 0 .../test/export/test_rsl_rl_export_flow.py | 8 +-- .../mhaiderbhai-cleanup-reach-tasks.major.rst | 20 ++++++ .../config/digit/loco_manip_env_cfg.py | 2 +- .../openarm/bimanual/joint_pos_env_cfg.py | 2 +- .../bimanual/reach_openarm_bi_env_cfg.py | 3 +- .../openarm/unimanual/joint_pos_env_cfg.py | 2 +- .../unimanual/reach_openarm_uni_env_cfg.py | 3 +- .../core/reach/config/franka/__init__.py | 8 +-- .../config/franka/agents/rsl_rl_ppo_cfg.py | 2 +- .../reach/config/franka/joint_pos_env_cfg.py | 2 +- .../core/reach/config/franka/osc_env_cfg.py | 9 +-- .../core/reach/config/ur_10/__init__.py | 4 +- .../reach/config/ur_10/joint_pos_env_cfg.py | 2 +- .../isaaclab_tasks/core/reach/mdp/__init__.py | 10 --- .../core/reach/mdp/__init__.pyi | 13 ---- .../isaaclab_tasks/core/reach/mdp/rewards.py | 70 ------------------- .../core/reach/reach_env_cfg.py | 12 ++-- .../isaaclab_tasks/utils/hydra.py | 2 +- .../test/benchmarking/configs.yaml | 4 +- 32 files changed, 158 insertions(+), 173 deletions(-) create mode 100644 source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst create mode 100644 source/isaaclab_rl/changelog.d/mhaiderbhai-cleanup-reach-tasks.skip create mode 100644 source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.py delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.pyi delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/rewards.py diff --git a/docs/source/features/hydra.rst b/docs/source/features/hydra.rst index 4676e884d6d6..ca68891f2e74 100644 --- a/docs/source/features/hydra.rst +++ b/docs/source/features/hydra.rst @@ -216,7 +216,7 @@ override is given: .. code-block:: bash # Use Newton physics backend - python train.py --task=Isaac-Reach-Franka-v0 env.physics=newton_mjwarp + python train.py --task=Isaac-Reach-Franka env.physics=newton_mjwarp The ``default`` field can be set to ``None`` to make an optional feature that is disabled unless explicitly selected: @@ -236,10 +236,10 @@ disabled unless explicitly selected: .. code-block:: bash # camera is None -- no camera overhead - python train.py --task=Isaac-Reach-Franka-v0 + python train.py --task=Isaac-Reach-Franka # activate camera with the "large" preset - python train.py --task=Isaac-Reach-Franka-v0 env.scene.camera=large + python train.py --task=Isaac-Reach-Franka env.scene.camera=large .. _hydra-backend-solver-presets: diff --git a/docs/source/how-to/wrap_rl_env.rst b/docs/source/how-to/wrap_rl_env.rst index 54433dfe0334..a7594df0b823 100644 --- a/docs/source/how-to/wrap_rl_env.rst +++ b/docs/source/how-to/wrap_rl_env.rst @@ -36,8 +36,8 @@ For example, here is how you would wrap an environment to enforce that reset is from isaaclab_tasks.utils import load_cfg_from_registry # create base environment - cfg = load_cfg_from_registry("Isaac-Reach-Franka-v0", "env_cfg_entry_point") - env = gym.make("Isaac-Reach-Franka-v0", cfg=cfg) + cfg = load_cfg_from_registry("Isaac-Reach-Franka", "env_cfg_entry_point") + env = gym.make("Isaac-Reach-Franka", cfg=cfg) # wrap environment to enforce that reset is called before step env = gym.wrappers.OrderEnforcing(env) @@ -61,7 +61,7 @@ To use the wrapper, you need to first install ``ffmpeg``. On Ubuntu, you can ins By default, when running an environment in headless mode, the Omniverse viewport is disabled. This is done to improve performance by avoiding unnecessary rendering. - We notice the following performance in different rendering modes with the ``Isaac-Reach-Franka-v0`` environment + We notice the following performance in different rendering modes with the ``Isaac-Reach-Franka`` environment using an RTX 3090 GPU: * No GUI execution without off-screen rendering enabled: ~65,000 FPS @@ -86,7 +86,7 @@ After adjusting the parameters, you can record videos by wrapping the environmen :class:`gymnasium.wrappers.RecordVideo` wrapper and enabling the off-screen rendering flag. Additionally, you need to specify the render mode of the environment as ``"rgb_array"``. -As an example, the following code records a video of the ``Isaac-Reach-Franka-v0`` environment +As an example, the following code records a video of the ``Isaac-Reach-Franka`` environment for 200 steps, and saves it in the ``videos`` folder at a step interval of 1500 steps. .. code:: python diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index 6e524b393c91..03526aba4bd1 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -300,8 +300,8 @@ for the lift-cube environment: .. |cabi_openarm_uni| image:: ../_static/tasks/manipulation/openarm_uni_open_drawer.jpg .. |g1_assemble_trocar| image:: ../_static/tasks/manipulation/g1_assemble_trocar.jpg -.. |reach-franka-link| replace:: `Isaac-Reach-Franka-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py>`__ -.. |reach-ur10-link| replace:: `Isaac-Reach-UR10-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py>`__ +.. |reach-franka-link| replace:: `Isaac-Reach-Franka <../../../source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py>`__ +.. |reach-ur10-link| replace:: `Isaac-Reach-UR10 <../../../source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py>`__ .. |deploy-reach-ur10e-link| replace:: `Isaac-Deploy-Reach-UR10e-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/reach/config/ur_10e/joint_pos_env_cfg.py>`__ .. |lift-cube-link| replace:: `Isaac-Lift-Cube-Franka-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py>`__ .. |lift-cube-ik-abs-link| replace:: `Isaac-Lift-Cube-Franka-IK-Abs-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/franka/ik_abs_env_cfg.py>`__ @@ -1178,13 +1178,13 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - - **physics=** ``newton_mjwarp``, ``physx`` - * - Isaac-Reach-Franka-OSC-v0 - - Isaac-Reach-Franka-OSC-Play-v0 + * - Isaac-Reach-Franka-OSC + - Isaac-Reach-Franka-OSC-Play - Manager Based - **rsl_rl** (PPO) - **physics=** ``newton_mjwarp``, ``physx`` - * - Isaac-Reach-Franka-v0 - - Isaac-Reach-Franka-Play-v0 + * - Isaac-Reach-Franka + - Isaac-Reach-Franka-Play - Manager Based - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO) - **physics=** ``newton_mjwarp``, ``physx`` @@ -1198,8 +1198,8 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO) - - * - Isaac-Reach-UR10-v0 - - Isaac-Reach-UR10-Play-v0 + * - Isaac-Reach-UR10 + - Isaac-Reach-UR10-Play - Manager Based - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO) - **physics=** ``newton_mjwarp``, ``physx`` diff --git a/docs/source/overview/reinforcement-learning/rl_existing_scripts.rst b/docs/source/overview/reinforcement-learning/rl_existing_scripts.rst index 9b2bfba91587..f261d64192d9 100644 --- a/docs/source/overview/reinforcement-learning/rl_existing_scripts.rst +++ b/docs/source/overview/reinforcement-learning/rl_existing_scripts.rst @@ -119,7 +119,7 @@ RSL-RL ------ - Training an agent with - `RSL-RL `__ on ``Isaac-Reach-Franka-v0``: + `RSL-RL `__ on ``Isaac-Reach-Franka``: .. tab-set:: :sync-group: os @@ -132,13 +132,13 @@ RSL-RL # install python module (for rsl-rl) ./isaaclab.sh -i rsl_rl # run command for training - ./isaaclab.sh train --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --headless + ./isaaclab.sh train --rl_library rsl_rl --task Isaac-Reach-Franka --headless # run command for training with Newton backend - ./isaaclab.sh train --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --headless physics=newton_mjwarp + ./isaaclab.sh train --rl_library rsl_rl --task Isaac-Reach-Franka --headless physics=newton_mjwarp # run command for playing with 32 environments - ./isaaclab.sh play --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --num_envs 32 --load_run run_folder_name --checkpoint /PATH/TO/model.pt + ./isaaclab.sh play --rl_library rsl_rl --task Isaac-Reach-Franka --num_envs 32 --load_run run_folder_name --checkpoint /PATH/TO/model.pt # run command for recording video of a trained agent (requires installing `ffmpeg`) - ./isaaclab.sh play --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --headless --video --video_length 200 + ./isaaclab.sh play --rl_library rsl_rl --task Isaac-Reach-Franka --headless --video --video_length 200 .. tab-item:: :icon:`fa-brands fa-windows` Windows :sync: windows @@ -148,13 +148,13 @@ RSL-RL :: install python module (for rsl-rl) isaaclab.bat -i rsl_rl :: run command for training - isaaclab.bat train --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --headless + isaaclab.bat train --rl_library rsl_rl --task Isaac-Reach-Franka --headless :: run command for training with Newton backend - isaaclab.bat train --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --headless physics=newton_mjwarp + isaaclab.bat train --rl_library rsl_rl --task Isaac-Reach-Franka --headless physics=newton_mjwarp :: run command for playing with 32 environments - isaaclab.bat play --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --num_envs 32 --load_run run_folder_name --checkpoint /PATH/TO/model.pt + isaaclab.bat play --rl_library rsl_rl --task Isaac-Reach-Franka --num_envs 32 --load_run run_folder_name --checkpoint /PATH/TO/model.pt :: run command for recording video of a trained agent (requires installing `ffmpeg`) - isaaclab.bat play --rl_library rsl_rl --task Isaac-Reach-Franka-v0 --headless --video --video_length 200 + isaaclab.bat play --rl_library rsl_rl --task Isaac-Reach-Franka --headless --video --video_length 200 - Training and distilling an agent with `RSL-RL `__ on ``Isaac-Velocity-Flat-Anymal-D-v0``: @@ -198,7 +198,7 @@ SKRL ---- - Training an agent with - `SKRL `__ on ``Isaac-Reach-Franka-v0``: + `SKRL `__ on ``Isaac-Reach-Franka``: .. tab-set:: @@ -215,13 +215,13 @@ SKRL # install python module (for skrl) ./isaaclab.sh -i skrl # run command for training - ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka-v0 --headless + ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka --headless # run command for training with Newton backend - ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka-v0 --headless physics=newton_mjwarp + ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka --headless physics=newton_mjwarp # run command for playing with 32 environments - ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka-v0 --num_envs 32 --checkpoint /PATH/TO/model.pt + ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka --num_envs 32 --checkpoint /PATH/TO/model.pt # run command for recording video of a trained agent (requires installing `ffmpeg`) - ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka-v0 --headless --video --video_length 200 + ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka --headless --video --video_length 200 .. tab-item:: :icon:`fa-brands fa-windows` Windows :sync: windows @@ -231,13 +231,13 @@ SKRL :: install python module (for skrl) isaaclab.bat -i skrl :: run command for training - isaaclab.bat train --rl_library skrl --task Isaac-Reach-Franka-v0 --headless + isaaclab.bat train --rl_library skrl --task Isaac-Reach-Franka --headless :: run command for training with Newton backend - isaaclab.bat train --rl_library skrl --task Isaac-Reach-Franka-v0 --headless physics=newton_mjwarp + isaaclab.bat train --rl_library skrl --task Isaac-Reach-Franka --headless physics=newton_mjwarp :: run command for playing with 32 environments - isaaclab.bat play --rl_library skrl --task Isaac-Reach-Franka-v0 --num_envs 32 --checkpoint /PATH/TO/model.pt + isaaclab.bat play --rl_library skrl --task Isaac-Reach-Franka --num_envs 32 --checkpoint /PATH/TO/model.pt :: run command for recording video of a trained agent (requires installing `ffmpeg`) - isaaclab.bat play --rl_library skrl --task Isaac-Reach-Franka-v0 --headless --video --video_length 200 + isaaclab.bat play --rl_library skrl --task Isaac-Reach-Franka --headless --video --video_length 200 .. tab-item:: JAX @@ -285,13 +285,13 @@ SKRL .. code:: bash # run command for training - ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka-v0 --headless --ml_framework jax + ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka --headless --ml_framework jax # run command for training with Newton backend - ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka-v0 --headless --ml_framework jax presets=newton_mjwarp + ./isaaclab.sh train --rl_library skrl --task Isaac-Reach-Franka --headless --ml_framework jax presets=newton_mjwarp # run command for playing with 32 environments - ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka-v0 --num_envs 32 --ml_framework jax --checkpoint /PATH/TO/model.pt + ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka --num_envs 32 --ml_framework jax --checkpoint /PATH/TO/model.pt # run command for recording video of a trained agent (requires installing `ffmpeg`) - ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka-v0 --headless --ml_framework jax --video --video_length 200 + ./isaaclab.sh play --rl_library skrl --task Isaac-Reach-Franka --headless --ml_framework jax --video --video_length 200 - Training the multi-agent environment ``Isaac-Shadow-Hand-Over-Direct-v0`` with skrl: diff --git a/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst b/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst index 4a062e59b0d9..28beaf9ef778 100644 --- a/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst +++ b/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst @@ -104,7 +104,7 @@ For example, to export a UR10 reach policy: .. code-block:: bash ./isaaclab.sh -p scripts/reinforcement_learning/leapp/rsl_rl/export.py \ - --task Isaac-Reach-UR10-v0 \ + --task Isaac-Reach-UR10 \ --checkpoint logs/rsl_rl/ur10_reach/< date timestamp >/model_4999.pt .. tab-item:: :icon:`fa-brands fa-windows` Windows @@ -113,7 +113,7 @@ For example, to export a UR10 reach policy: .. code-block:: batch isaaclab.bat -p scripts\reinforcement_learning\leapp\rsl_rl\export.py ^ - --task Isaac-Reach-UR10-v0 ^ + --task Isaac-Reach-UR10 ^ --checkpoint logs\rsl_rl\ur10_reach\\model_4999.pt By default, the export artifacts are saved in the same directory as the checkpoint. The diff --git a/scripts/benchmarks/benchmark_hydra_resolve.py b/scripts/benchmarks/benchmark_hydra_resolve.py index 6b13705179fd..3379d7b438c5 100644 --- a/scripts/benchmarks/benchmark_hydra_resolve.py +++ b/scripts/benchmarks/benchmark_hydra_resolve.py @@ -82,7 +82,7 @@ class Case: Case("cartpole_rgb_direct", "Isaac-Cartpole-Camera-Direct", None, ("presets=rgb",)), Case("ant_manager", "Isaac-Ant"), Case("humanoid_manager", "Isaac-Humanoid", "rsl_rl_cfg_entry_point"), - Case("franka_reach", "Isaac-Reach-Franka-v0"), + Case("franka_reach", "Isaac-Reach-Franka"), Case("franka_lift_cube_agent", "Isaac-Lift-Cube-Franka-v0", "sb3_cfg_entry_point"), Case("kuka_allegro_lift", "Isaac-Dexsuite-Kuka-Allegro-Lift-v0", "rsl_rl_cfg_entry_point"), Case( diff --git a/scripts/benchmarks/benchmark_lazy_export.py b/scripts/benchmarks/benchmark_lazy_export.py index 8673f7dcf5dd..58a61c27cdec 100644 --- a/scripts/benchmarks/benchmark_lazy_export.py +++ b/scripts/benchmarks/benchmark_lazy_export.py @@ -49,7 +49,7 @@ "Isaac-Cartpole", "Isaac-Humanoid", "Isaac-Velocity-Flat-Anymal-D-v0", - "Isaac-Reach-Franka-v0", + "Isaac-Reach-Franka", "Isaac-Lift-Cube-Franka-v0", "Isaac-Dexsuite-Kuka-Allegro-Reorient-v0", "Isaac-Navigation-Flat-Anymal-C-v0", diff --git a/scripts/benchmarks/run_non_rl_benchmarks.sh b/scripts/benchmarks/run_non_rl_benchmarks.sh index a1cea1aab7cd..23c69a794f10 100755 --- a/scripts/benchmarks/run_non_rl_benchmarks.sh +++ b/scripts/benchmarks/run_non_rl_benchmarks.sh @@ -4,7 +4,7 @@ ROOT_DIR="${1:-./benchmarks}" OUTPUT_DIR="${ROOT_DIR}/isaaclab_non_rl" -TASKS="Isaac-Repose-Cube-Allegro-Direct-v0 Isaac-Ant-Direct Isaac-Cartpole-Direct Isaac-Humanoid-Direct Isaac-Ant Isaac-Cartpole Isaac-Humanoid Isaac-Velocity-Flat-Unitree-A1-v0 Isaac-Velocity-Flat-Anymal-B-v0 Isaac-Velocity-Flat-Anymal-C-v0 Isaac-Velocity-Flat-Anymal-D-v0 Isaac-Velocity-Flat-Cassie-v0 Isaac-Velocity-Flat-G1-v0 Isaac-Velocity-Flat-G1-v1 Isaac-Velocity-Flat-Unitree-Go1-v0 Isaac-Velocity-Flat-Unitree-Go2-v0 Isaac-Velocity-Flat-H1-v0 Isaac-Reach-Franka-v0 Isaac-Reach-UR10-v0" +TASKS="Isaac-Repose-Cube-Allegro-Direct-v0 Isaac-Ant-Direct Isaac-Cartpole-Direct Isaac-Humanoid-Direct Isaac-Ant Isaac-Cartpole Isaac-Humanoid Isaac-Velocity-Flat-Unitree-A1-v0 Isaac-Velocity-Flat-Anymal-B-v0 Isaac-Velocity-Flat-Anymal-C-v0 Isaac-Velocity-Flat-Anymal-D-v0 Isaac-Velocity-Flat-Cassie-v0 Isaac-Velocity-Flat-G1-v0 Isaac-Velocity-Flat-G1-v1 Isaac-Velocity-Flat-Unitree-Go1-v0 Isaac-Velocity-Flat-Unitree-Go2-v0 Isaac-Velocity-Flat-H1-v0 Isaac-Reach-Franka Isaac-Reach-UR10" NUM_ENVS="4096 8192 16384" NUM_FRAMES="100" diff --git a/scripts/benchmarks/run_training_benchmarks.sh b/scripts/benchmarks/run_training_benchmarks.sh index 8c60d539707e..e064bcbd4848 100755 --- a/scripts/benchmarks/run_training_benchmarks.sh +++ b/scripts/benchmarks/run_training_benchmarks.sh @@ -2,7 +2,7 @@ ROOT_DIR="${1:-./benchmarks}" OUTPUT_DIR="${ROOT_DIR}/isaaclab_rsl_rl_training" -TASKS="Isaac-Repose-Cube-Allegro-Direct-v0 Isaac-Ant-Direct Isaac-Cartpole-Direct Isaac-Humanoid-Direct Isaac-Ant Isaac-Cartpole Isaac-Humanoid Isaac-Velocity-Flat-Unitree-A1-v0 Isaac-Velocity-Flat-Anymal-B-v0 Isaac-Velocity-Flat-Anymal-C-v0 Isaac-Velocity-Flat-Anymal-D-v0 Isaac-Velocity-Flat-Cassie-v0 Isaac-Velocity-Flat-G1-v0 Isaac-Velocity-Flat-G1-v1 Isaac-Velocity-Flat-Unitree-Go1-v0 Isaac-Velocity-Flat-Unitree-Go2-v0 Isaac-Velocity-Flat-H1-v0 Isaac-Reach-Franka-v0 Isaac-Reach-UR10-v0" +TASKS="Isaac-Repose-Cube-Allegro-Direct-v0 Isaac-Ant-Direct Isaac-Cartpole-Direct Isaac-Humanoid-Direct Isaac-Ant Isaac-Cartpole Isaac-Humanoid Isaac-Velocity-Flat-Unitree-A1-v0 Isaac-Velocity-Flat-Anymal-B-v0 Isaac-Velocity-Flat-Anymal-C-v0 Isaac-Velocity-Flat-Anymal-D-v0 Isaac-Velocity-Flat-Cassie-v0 Isaac-Velocity-Flat-G1-v0 Isaac-Velocity-Flat-G1-v1 Isaac-Velocity-Flat-Unitree-Go1-v0 Isaac-Velocity-Flat-Unitree-Go2-v0 Isaac-Velocity-Flat-H1-v0 Isaac-Reach-Franka Isaac-Reach-UR10" NUM_ENV="4096" ITERATIONS="500" diff --git a/source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst b/source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst new file mode 100644 index 000000000000..6b787364e603 --- /dev/null +++ b/source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst @@ -0,0 +1,8 @@ +Added +^^^^^ + +* Added the pose-tracking reward terms :func:`~isaaclab.envs.mdp.rewards.position_command_error`, + :func:`~isaaclab.envs.mdp.rewards.position_command_error_tanh` and + :func:`~isaaclab.envs.mdp.rewards.orientation_command_error` to the shared MDP reward terms. They + track a body pose against a pose command and complement the existing velocity-tracking terms. The + reach task previously defined these locally. diff --git a/source/isaaclab/isaaclab/envs/mdp/__init__.pyi b/source/isaaclab/isaaclab/envs/mdp/__init__.pyi index 5b7e28e29e4a..e9ea306a941e 100644 --- a/source/isaaclab/isaaclab/envs/mdp/__init__.pyi +++ b/source/isaaclab/isaaclab/envs/mdp/__init__.pyi @@ -127,6 +127,9 @@ __all__ = [ "joint_vel_l2", "joint_vel_limits", "lin_vel_z_l2", + "orientation_command_error", + "position_command_error", + "position_command_error_tanh", "track_ang_vel_z_exp", "track_lin_vel_xy_exp", "undesired_contacts", @@ -274,6 +277,9 @@ from .rewards import ( joint_vel_l2, joint_vel_limits, lin_vel_z_l2, + orientation_command_error, + position_command_error, + position_command_error_tanh, track_ang_vel_z_exp, track_lin_vel_xy_exp, undesired_contacts, diff --git a/source/isaaclab/isaaclab/envs/mdp/rewards.py b/source/isaaclab/isaaclab/envs/mdp/rewards.py index 4645e4fd805e..7d42f1e5a5e3 100644 --- a/source/isaaclab/isaaclab/envs/mdp/rewards.py +++ b/source/isaaclab/isaaclab/envs/mdp/rewards.py @@ -18,6 +18,7 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.managers.manager_base import ManagerTermBase from isaaclab.managers.manager_term_cfg import RewardTermCfg +from isaaclab.utils.math import combine_frame_transforms, quat_error_magnitude, quat_mul if TYPE_CHECKING: from isaaclab.assets import Articulation, RigidObject @@ -336,3 +337,55 @@ def track_ang_vel_z_exp( env.command_manager.get_command(command_name)[:, 2] - asset.data.root_ang_vel_b.torch[:, 2] ) return torch.exp(-ang_vel_error / std**2) + + +""" +Pose-tracking rewards. +""" + + +def position_command_error(env: ManagerBasedRLEnv, command_name: str, asset_cfg: SceneEntityCfg) -> torch.Tensor: + """Penalize tracking of the position error using the L2 norm. + + The error [m] is the L2 norm between the commanded position (resolved into the world frame from the + asset's root pose) and the current position of the asset's body in the world frame. The command is + expected to be a pose command whose first three entries are the desired position in the root frame. + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject = env.scene[asset_cfg.name] + command = env.command_manager.get_command(command_name) + # obtain the desired and current positions in the world frame + des_pos_b = command[:, :3] + des_pos_w, _ = combine_frame_transforms(asset.data.root_pos_w.torch, asset.data.root_quat_w.torch, des_pos_b) + curr_pos_w = asset.data.body_pos_w.torch[:, asset_cfg.body_ids[0]] # type: ignore + return torch.linalg.norm(curr_pos_w - des_pos_w, dim=1) + + +def position_command_error_tanh( + env: ManagerBasedRLEnv, std: float, command_name: str, asset_cfg: SceneEntityCfg +) -> torch.Tensor: + """Reward tracking of the position error using the tanh kernel. + + The position error [m] is computed as in :func:`position_command_error` and mapped through a tanh + kernel with standard deviation ``std`` [m], yielding a bounded reward in ``[0, 1)``. + """ + distance = position_command_error(env, command_name, asset_cfg) + return 1 - torch.tanh(distance / std) + + +def orientation_command_error(env: ManagerBasedRLEnv, command_name: str, asset_cfg: SceneEntityCfg) -> torch.Tensor: + """Penalize tracking of the orientation error using the shortest-path quaternion distance. + + The error [rad] is the shortest-path angle between the commanded orientation (resolved into the + world frame from the asset's root pose) and the current orientation of the asset's body in the world + frame. The command is expected to be a pose command whose entries ``[3:7]`` are the desired + orientation quaternion in the root frame. + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject = env.scene[asset_cfg.name] + command = env.command_manager.get_command(command_name) + # obtain the desired and current orientations in the world frame + des_quat_b = command[:, 3:7] + des_quat_w = quat_mul(asset.data.root_quat_w.torch, des_quat_b) + curr_quat_w = asset.data.body_quat_w.torch[:, asset_cfg.body_ids[0]] # type: ignore + return quat_error_magnitude(curr_quat_w, des_quat_w) diff --git a/source/isaaclab_rl/changelog.d/mhaiderbhai-cleanup-reach-tasks.skip b/source/isaaclab_rl/changelog.d/mhaiderbhai-cleanup-reach-tasks.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py b/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py index ec6021021f2c..64aa39bccf0f 100644 --- a/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py +++ b/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py @@ -78,10 +78,10 @@ "Isaac-Velocity-Rough-Unitree-Go2-v0", "Isaac-Velocity-Rough-Unitree-Go2-Play-v0", # Manipulation Reach - "Isaac-Reach-Franka-v0", - "Isaac-Reach-Franka-Play-v0", - "Isaac-Reach-UR10-v0", - "Isaac-Reach-UR10-Play-v0", + "Isaac-Reach-Franka", + "Isaac-Reach-Franka-Play", + "Isaac-Reach-UR10", + "Isaac-Reach-UR10-Play", # Manipulation Lift "Isaac-Lift-Cube-Franka-v0", "Isaac-Lift-Cube-Franka-Play-v0", diff --git a/source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst b/source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst new file mode 100644 index 000000000000..bff7031da51e --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst @@ -0,0 +1,20 @@ +Changed +^^^^^^^ + +* **Breaking:** Renamed the reach Gym environment IDs to drop the ``-v0`` version suffix. The + robot name is kept in the ID and the manager-based workflow carries no workflow suffix. Update + ``gym.make`` / ``--task`` calls: + + * ``Isaac-Reach-Franka-v0`` → ``Isaac-Reach-Franka``. + * ``Isaac-Reach-Franka-Play-v0`` → ``Isaac-Reach-Franka-Play``. + * ``Isaac-Reach-Franka-OSC-v0`` → ``Isaac-Reach-Franka-OSC``. + * ``Isaac-Reach-Franka-OSC-Play-v0`` → ``Isaac-Reach-Franka-OSC-Play``. + * ``Isaac-Reach-UR10-v0`` → ``Isaac-Reach-UR10``. + * ``Isaac-Reach-UR10-Play-v0`` → ``Isaac-Reach-UR10-Play``. +* Renamed the RSL-RL experiment name for the Franka reach task from ``franka_reach`` to + ``reach_franka`` so it matches the other Franka reach agent configs and the UR10 reach task. +* **Breaking:** Moved the reach pose-tracking reward terms ``position_command_error``, + ``position_command_error_tanh`` and ``orientation_command_error`` to the shared + :mod:`isaaclab.envs.mdp` terms and removed the ``isaaclab_tasks.core.reach.mdp`` package. Import + these terms from :mod:`isaaclab.envs.mdp` instead, e.g. replace + ``import isaaclab_tasks.core.reach.mdp as mdp`` with ``import isaaclab.envs.mdp as mdp``. diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_tracking/config/digit/loco_manip_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_tracking/config/digit/loco_manip_env_cfg.py index 8b4472f1c7ee..1e7b572ed427 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_tracking/config/digit/loco_manip_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_tracking/config/digit/loco_manip_env_cfg.py @@ -5,6 +5,7 @@ import math +import isaaclab.envs.mdp as manipulation_mdp from isaaclab.managers import EventTermCfg, SceneEntityCfg from isaaclab.managers import ObservationGroupCfg as ObsGroup from isaaclab.managers import ObservationTermCfg as ObsTerm @@ -12,7 +13,6 @@ from isaaclab.utils.configclass import configclass from isaaclab.utils.noise import UniformNoiseCfg as Unoise -import isaaclab_tasks.core.reach.mdp as manipulation_mdp import isaaclab_tasks.core.velocity.mdp as mdp from isaaclab_tasks.core.velocity.config.digit.rough_env_cfg import DigitRewards, DigitRoughEnvCfg from isaaclab_tasks.core.velocity.velocity_env_cfg import EventsCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/joint_pos_env_cfg.py index e26d496f2c63..3c9bcb25caa0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/joint_pos_env_cfg.py @@ -7,9 +7,9 @@ # Pre-defined configs ## +import isaaclab.envs.mdp as mdp from isaaclab.utils.configclass import configclass -import isaaclab_tasks.core.reach.mdp as mdp from isaaclab_tasks.contrib.reach.config.openarm.bimanual.reach_openarm_bi_env_cfg import ReachEnvCfg from isaaclab_assets.robots.openarm import OPENARM_BI_HIGH_PD_CFG diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py index 70cc0bbb8f5d..bacc155f7270 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py @@ -10,6 +10,7 @@ import math from dataclasses import MISSING +import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.envs import ManagerBasedRLEnvCfg @@ -25,8 +26,6 @@ from isaaclab.utils.configclass import configclass from isaaclab.utils.noise import UniformNoiseCfg as Unoise -import isaaclab_tasks.core.reach.mdp as mdp - ## # Scene definition ## diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/joint_pos_env_cfg.py index 7a97440e04fc..770b189961cc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/joint_pos_env_cfg.py @@ -3,10 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +import isaaclab.envs.mdp as mdp from isaaclab.assets.articulation import ArticulationCfg from isaaclab.utils.configclass import configclass -import isaaclab_tasks.core.reach.mdp as mdp from isaaclab_tasks.contrib.reach.config.openarm.unimanual.reach_openarm_uni_env_cfg import ( ReachEnvCfg, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py index bbd8e17a0e02..b2f933cf9db6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py @@ -10,6 +10,7 @@ import math from dataclasses import MISSING +import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.envs import ManagerBasedRLEnvCfg @@ -26,8 +27,6 @@ from isaaclab.utils.configclass import configclass from isaaclab.utils.noise import UniformNoiseCfg as Unoise -import isaaclab_tasks.core.reach.mdp as mdp - ## # Scene definition ## diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/__init__.py index c00f7e6ad1da..5e28dc985b5c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/__init__.py @@ -16,7 +16,7 @@ ## gym.register( - id="Isaac-Reach-Franka-v0", + id="Isaac-Reach-Franka", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ @@ -28,7 +28,7 @@ ) gym.register( - id="Isaac-Reach-Franka-Play-v0", + id="Isaac-Reach-Franka-Play", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ @@ -45,7 +45,7 @@ ## gym.register( - id="Isaac-Reach-Franka-OSC-v0", + id="Isaac-Reach-Franka-OSC", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ @@ -55,7 +55,7 @@ ) gym.register( - id="Isaac-Reach-Franka-OSC-Play-v0", + id="Isaac-Reach-Franka-OSC-Play", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/agents/rsl_rl_ppo_cfg.py index de9445906e8f..ccce6ac2b32b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/agents/rsl_rl_ppo_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/agents/rsl_rl_ppo_cfg.py @@ -13,7 +13,7 @@ class FrankaReachPPORunnerCfg(RslRlOnPolicyRunnerCfg): num_steps_per_env = 24 max_iterations = 1000 save_interval = 50 - experiment_name = "franka_reach" + experiment_name = "reach_franka" run_name = "" actor = RslRlMLPModelCfg( hidden_dims=[64, 64], diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py index f75ff4c1df89..105a3753afb8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py @@ -5,9 +5,9 @@ import math +import isaaclab.envs.mdp as mdp from isaaclab.utils.configclass import configclass -import isaaclab_tasks.core.reach.mdp as mdp from isaaclab_tasks.core.reach.reach_env_cfg import ReachEnvCfg ## diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py index 24b94f266433..88d8a70e8f29 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py @@ -9,11 +9,6 @@ from . import joint_pos_env_cfg -## -# Pre-defined configs -## -from isaaclab_assets.robots.franka import FRANKA_PANDA_CFG # isort: skip - @configclass class FrankaReachEnvCfg(joint_pos_env_cfg.FrankaReachEnvCfg): @@ -21,9 +16,7 @@ def __post_init__(self): # post init of parent super().__post_init__() - # Set Franka as robot - # We remove stiffness and damping for the shoulder and forearm joints for effort control - self.scene.robot = FRANKA_PANDA_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + # Remove stiffness and damping for the shoulder and forearm joints for effort control self.scene.robot.actuators["panda_shoulder"].stiffness = 0.0 self.scene.robot.actuators["panda_shoulder"].damping = 0.0 self.scene.robot.actuators["panda_forearm"].stiffness = 0.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/__init__.py index fafe5b75820c..16a08fac8bea 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/__init__.py @@ -12,7 +12,7 @@ ## gym.register( - id="Isaac-Reach-UR10-v0", + id="Isaac-Reach-UR10", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ @@ -24,7 +24,7 @@ ) gym.register( - id="Isaac-Reach-UR10-Play-v0", + id="Isaac-Reach-UR10-Play", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py index 5a54b213f869..16419db288da 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py @@ -5,9 +5,9 @@ import math +import isaaclab.envs.mdp as mdp from isaaclab.utils.configclass import configclass -import isaaclab_tasks.core.reach.mdp as mdp from isaaclab_tasks.core.reach.reach_env_cfg import ReachEnvCfg ## diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.py deleted file mode 100644 index 8f9a146abdc8..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.py +++ /dev/null @@ -1,10 +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 - -"""This sub-module contains the functions that are specific to the locomotion environments.""" - -from isaaclab.utils.module import lazy_export - -lazy_export() diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.pyi b/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.pyi deleted file mode 100644 index 90535ff4c7e0..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/__init__.pyi +++ /dev/null @@ -1,13 +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 - -__all__ = [ - "orientation_command_error", - "position_command_error", - "position_command_error_tanh", -] - -from .rewards import orientation_command_error, position_command_error, position_command_error_tanh -from isaaclab.envs.mdp import * diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/rewards.py deleted file mode 100644 index 3238523134d5..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/mdp/rewards.py +++ /dev/null @@ -1,70 +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 - -from __future__ import annotations - -from typing import TYPE_CHECKING - -import torch - -from isaaclab.managers import SceneEntityCfg -from isaaclab.utils.math import combine_frame_transforms, quat_error_magnitude, quat_mul - -if TYPE_CHECKING: - from isaaclab.assets import RigidObject - from isaaclab.envs import ManagerBasedRLEnv - - -def position_command_error(env: ManagerBasedRLEnv, command_name: str, asset_cfg: SceneEntityCfg) -> torch.Tensor: - """Penalize tracking of the position error using L2-norm. - - The function computes the position error between the desired position (from the command) and the - current position of the asset's body (in world frame). The position error is computed as the L2-norm - of the difference between the desired and current positions. - """ - # extract the asset (to enable type hinting) - asset: RigidObject = env.scene[asset_cfg.name] - command = env.command_manager.get_command(command_name) - # obtain the desired and current positions - des_pos_b = command[:, :3] - des_pos_w, _ = combine_frame_transforms(asset.data.root_pos_w.torch, asset.data.root_quat_w.torch, des_pos_b) - curr_pos_w = asset.data.body_pos_w.torch[:, asset_cfg.body_ids[0]] # type: ignore - return torch.linalg.norm(curr_pos_w - des_pos_w, dim=1) - - -def position_command_error_tanh( - env: ManagerBasedRLEnv, std: float, command_name: str, asset_cfg: SceneEntityCfg -) -> torch.Tensor: - """Reward tracking of the position using the tanh kernel. - - The function computes the position error between the desired position (from the command) and the - current position of the asset's body (in world frame) and maps it with a tanh kernel. - """ - # extract the asset (to enable type hinting) - asset: RigidObject = env.scene[asset_cfg.name] - command = env.command_manager.get_command(command_name) - # obtain the desired and current positions - des_pos_b = command[:, :3] - des_pos_w, _ = combine_frame_transforms(asset.data.root_pos_w.torch, asset.data.root_quat_w.torch, des_pos_b) - curr_pos_w = asset.data.body_pos_w.torch[:, asset_cfg.body_ids[0]] # type: ignore - distance = torch.linalg.norm(curr_pos_w - des_pos_w, dim=1) - return 1 - torch.tanh(distance / std) - - -def orientation_command_error(env: ManagerBasedRLEnv, command_name: str, asset_cfg: SceneEntityCfg) -> torch.Tensor: - """Penalize tracking orientation error using shortest path. - - The function computes the orientation error between the desired orientation (from the command) and the - current orientation of the asset's body (in world frame). The orientation error is computed as the shortest - path between the desired and current orientations. - """ - # extract the asset (to enable type hinting) - asset: RigidObject = env.scene[asset_cfg.name] - command = env.command_manager.get_command(command_name) - # obtain the desired and current orientations - des_quat_b = command[:, 3:7] - des_quat_w = quat_mul(asset.data.root_quat_w.torch, des_quat_b) - curr_quat_w = asset.data.body_quat_w.torch[:, asset_cfg.body_ids[0]] # type: ignore - return quat_error_magnitude(curr_quat_w, des_quat_w) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py index eb5d38b20c9d..99e6a9be13e8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py @@ -8,6 +8,7 @@ from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg from isaaclab_physx.physics import PhysxCfg +import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.devices import DevicesCfg @@ -24,18 +25,15 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import CollisionPropertiesCfg, RigidBodyPropertiesCfg, UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass from isaaclab.utils.noise import UniformNoiseCfg as Unoise -import isaaclab_tasks.core.reach.mdp as mdp from isaaclab_tasks.utils import PresetCfg @configclass class ReachPhysicsCfg(PresetCfg): - default: PhysxCfg = PhysxCfg(bounce_threshold_velocity=0.2) physx: PhysxCfg = PhysxCfg(bounce_threshold_velocity=0.2) newton_mjwarp: NewtonCfg = NewtonCfg( @@ -50,6 +48,8 @@ class ReachPhysicsCfg(PresetCfg): debug_mode=False, ) + default = physx + ## # Scene definition @@ -61,7 +61,7 @@ class TableCfg(PresetCfg): physx = AssetBaseCfg( prim_path="/World/envs/env_.*/Table", init_state=AssetBaseCfg.InitialStateCfg(pos=(0.5, 0, 0), rot=(0, 0, 0.707, 0.707)), - spawn=UsdFileCfg( + spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd", ), ) @@ -73,8 +73,8 @@ class TableCfg(PresetCfg): ), spawn=sim_utils.CuboidCfg( size=(0.9, 1.3, 1.00), - collision_props=CollisionPropertiesCfg(), - rigid_props=RigidBodyPropertiesCfg(rigid_body_enabled=True), + collision_props=sim_utils.CollisionPropertiesCfg(), + rigid_props=sim_utils.RigidBodyPropertiesCfg(rigid_body_enabled=True), ), actuators={}, articulation_root_prim_path="", diff --git a/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py b/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py index 5d965b7dd332..a809c620b20b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py +++ b/source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py @@ -489,7 +489,7 @@ def hydra_task_config(task_name: str, agent_cfg_entry_point: str) -> Callable: """Decorator for Hydra config with REPLACE-only preset semantics. Args: - task_name: Task name (e.g., "Isaac-Reach-Franka-v0") + task_name: Task name (e.g., "Isaac-Reach-Franka") agent_cfg_entry_point: Agent config entry point key Returns: diff --git a/source/isaaclab_tasks/test/benchmarking/configs.yaml b/source/isaaclab_tasks/test/benchmarking/configs.yaml index 3dacf5ee9ec0..0622fc29e617 100644 --- a/source/isaaclab_tasks/test/benchmarking/configs.yaml +++ b/source/isaaclab_tasks/test/benchmarking/configs.yaml @@ -180,7 +180,7 @@ full: episode_length: 150 upper_thresholds: duration: 1500 - Isaac-Reach-Franka-OSC-v0: + Isaac-Reach-Franka-OSC: max_iterations: 1000 lower_thresholds: reward: 0.25 @@ -217,7 +217,7 @@ full: upper_thresholds: duration: 1800 # Manipulation tasks - UR10 - Isaac-Reach-UR10-v0: + Isaac-Reach-UR10: max_iterations: 1000 lower_thresholds: reward: 0.25 From 1c5f8b41641504fcd29df23b64b54652ace2c5ad Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Sun, 7 Jun 2026 06:32:44 +0000 Subject: [PATCH 08/40] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 6.4.0 → 6.5.0 - isaaclab_tasks: 3.0.0 → 4.0.0 --- ...haiderbhai-pose-tracking-rewards.minor.rst | 8 ------ source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 13 ++++++++++ source/isaaclab/pyproject.toml | 2 +- .../mhaiderbhai-cleanup-reach-tasks.skip | 0 .../mhaiderbhai-cleanup-reach-tasks.major.rst | 20 --------------- source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 25 +++++++++++++++++++ source/isaaclab_tasks/pyproject.toml | 2 +- 9 files changed, 42 insertions(+), 32 deletions(-) delete mode 100644 source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst delete mode 100644 source/isaaclab_rl/changelog.d/mhaiderbhai-cleanup-reach-tasks.skip delete mode 100644 source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst diff --git a/source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst b/source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst deleted file mode 100644 index 6b787364e603..000000000000 --- a/source/isaaclab/changelog.d/mhaiderbhai-pose-tracking-rewards.minor.rst +++ /dev/null @@ -1,8 +0,0 @@ -Added -^^^^^ - -* Added the pose-tracking reward terms :func:`~isaaclab.envs.mdp.rewards.position_command_error`, - :func:`~isaaclab.envs.mdp.rewards.position_command_error_tanh` and - :func:`~isaaclab.envs.mdp.rewards.orientation_command_error` to the shared MDP reward terms. They - track a body pose against a pose command and complement the existing velocity-tracking terms. The - reach task previously defined these locally. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 2fd1fa73394e..b360527edc03 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "6.4.0" +version = "6.5.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 587fb0c52314..e2c217487ab2 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,19 @@ Changelog --------- +6.5.0 (2026-06-07) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added the pose-tracking reward terms :func:`~isaaclab.envs.mdp.rewards.position_command_error`, + :func:`~isaaclab.envs.mdp.rewards.position_command_error_tanh` and + :func:`~isaaclab.envs.mdp.rewards.orientation_command_error` to the shared MDP reward terms. They + track a body pose against a pose command and complement the existing velocity-tracking terms. The + reach task previously defined these locally. + + 6.4.0 (2026-06-06) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/pyproject.toml b/source/isaaclab/pyproject.toml index 2dd4ebcedd62..935d83f0f5b9 100644 --- a/source/isaaclab/pyproject.toml +++ b/source/isaaclab/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab" -version = "6.4.0" +version = "6.5.0" description = "Extension providing main framework interfaces and abstractions for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_rl/changelog.d/mhaiderbhai-cleanup-reach-tasks.skip b/source/isaaclab_rl/changelog.d/mhaiderbhai-cleanup-reach-tasks.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst b/source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst deleted file mode 100644 index bff7031da51e..000000000000 --- a/source/isaaclab_tasks/changelog.d/mhaiderbhai-cleanup-reach-tasks.major.rst +++ /dev/null @@ -1,20 +0,0 @@ -Changed -^^^^^^^ - -* **Breaking:** Renamed the reach Gym environment IDs to drop the ``-v0`` version suffix. The - robot name is kept in the ID and the manager-based workflow carries no workflow suffix. Update - ``gym.make`` / ``--task`` calls: - - * ``Isaac-Reach-Franka-v0`` → ``Isaac-Reach-Franka``. - * ``Isaac-Reach-Franka-Play-v0`` → ``Isaac-Reach-Franka-Play``. - * ``Isaac-Reach-Franka-OSC-v0`` → ``Isaac-Reach-Franka-OSC``. - * ``Isaac-Reach-Franka-OSC-Play-v0`` → ``Isaac-Reach-Franka-OSC-Play``. - * ``Isaac-Reach-UR10-v0`` → ``Isaac-Reach-UR10``. - * ``Isaac-Reach-UR10-Play-v0`` → ``Isaac-Reach-UR10-Play``. -* Renamed the RSL-RL experiment name for the Franka reach task from ``franka_reach`` to - ``reach_franka`` so it matches the other Franka reach agent configs and the UR10 reach task. -* **Breaking:** Moved the reach pose-tracking reward terms ``position_command_error``, - ``position_command_error_tanh`` and ``orientation_command_error`` to the shared - :mod:`isaaclab.envs.mdp` terms and removed the ``isaaclab_tasks.core.reach.mdp`` package. Import - these terms from :mod:`isaaclab.envs.mdp` instead, e.g. replace - ``import isaaclab_tasks.core.reach.mdp as mdp`` with ``import isaaclab.envs.mdp as mdp``. diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index 5a19dcdbbca7..82e42b2adf75 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "3.0.0" +version = "4.0.0" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 2134ed07bd52..ca0b9005f4d6 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,31 @@ Changelog --------- +4.0.0 (2026-06-07) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* **Breaking:** Renamed the reach Gym environment IDs to drop the ``-v0`` version suffix. The + robot name is kept in the ID and the manager-based workflow carries no workflow suffix. Update + ``gym.make`` / ``--task`` calls: + + * ``Isaac-Reach-Franka-v0`` → ``Isaac-Reach-Franka``. + * ``Isaac-Reach-Franka-Play-v0`` → ``Isaac-Reach-Franka-Play``. + * ``Isaac-Reach-Franka-OSC-v0`` → ``Isaac-Reach-Franka-OSC``. + * ``Isaac-Reach-Franka-OSC-Play-v0`` → ``Isaac-Reach-Franka-OSC-Play``. + * ``Isaac-Reach-UR10-v0`` → ``Isaac-Reach-UR10``. + * ``Isaac-Reach-UR10-Play-v0`` → ``Isaac-Reach-UR10-Play``. +* Renamed the RSL-RL experiment name for the Franka reach task from ``franka_reach`` to + ``reach_franka`` so it matches the other Franka reach agent configs and the UR10 reach task. +* **Breaking:** Moved the reach pose-tracking reward terms ``position_command_error``, + ``position_command_error_tanh`` and ``orientation_command_error`` to the shared + :mod:`isaaclab.envs.mdp` terms and removed the ``isaaclab_tasks.core.reach.mdp`` package. Import + these terms from :mod:`isaaclab.envs.mdp` instead, e.g. replace + ``import isaaclab_tasks.core.reach.mdp as mdp`` with ``import isaaclab.envs.mdp as mdp``. + + 3.0.0 (2026-06-06) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/pyproject.toml b/source/isaaclab_tasks/pyproject.toml index 1069c15136d1..c65fa38e3819 100644 --- a/source/isaaclab_tasks/pyproject.toml +++ b/source/isaaclab_tasks/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_tasks" -version = "3.0.0" +version = "4.0.0" description = "Extension containing suite of environments for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] From c2529ff00ea1702c556458362ee3775eb7614b6e Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Sun, 7 Jun 2026 17:08:11 +0800 Subject: [PATCH 09/40] Bumps versions for released Isaac Sim 6.0 and Newton 1.2.1 (#6015) # Description Updates references of Isaac Sim pip wheel to point to the latest release 6.0.0.1 build. Updates staging S3 path to production. Updates Newton 1.2.1 to released pip wheel. ## Type of change - Bug fix (non-breaking change which fixes an issue) - Documentation update ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- apps/isaaclab.python.headless.kit | 6 +++--- apps/isaaclab.python.headless.rendering.kit | 6 +++--- apps/isaaclab.python.kit | 6 +++--- apps/isaaclab.python.rendering.kit | 6 +++--- apps/isaaclab.python.xr.openxr.headless.kit | 6 +++--- apps/isaaclab.python.xr.openxr.kit | 6 +++--- docs/_extensions/isaaclab_docs.py | 4 ++-- .../physical-backends/newton/installation.rst | 2 +- docs/source/overview/environments.rst | 2 ++ .../overview/imitation-learning/humanoids_imitation.rst | 6 +++--- docs/source/overview/imitation-learning/skillgen.rst | 2 +- .../overview/imitation-learning/teleop_imitation.rst | 2 +- .../setup/installation/isaaclab_pip_installation.rst | 2 +- docs/source/setup/installation/pip_installation.rst | 2 +- .../07_visualizers/run_tiled_camera_visualizer.py | 3 +-- source/isaaclab_newton/pyproject.toml | 2 +- source/isaaclab_physx/pyproject.toml | 2 +- source/isaaclab_visualizers/pyproject.toml | 8 ++++---- tools/wheel_builder/res/python_packages.toml | 6 +++--- 19 files changed, 40 insertions(+), 39 deletions(-) diff --git a/apps/isaaclab.python.headless.kit b/apps/isaaclab.python.headless.kit index bce5c800c74b..2d0858512ede 100644 --- a/apps/isaaclab.python.headless.kit +++ b/apps/isaaclab.python.headless.kit @@ -211,6 +211,6 @@ enabled=true # Enable this for DLSS # set the S3 directory manually to the latest published S3 # note: this is done to ensure prior versions of Isaac Sim still use the latest assets [settings] -persistent.isaac.asset_root.default = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.cloud = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.nvidia = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.default = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.cloud = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.nvidia = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" diff --git a/apps/isaaclab.python.headless.rendering.kit b/apps/isaaclab.python.headless.rendering.kit index 61fe20d00671..9bb0a3692432 100644 --- a/apps/isaaclab.python.headless.rendering.kit +++ b/apps/isaaclab.python.headless.rendering.kit @@ -161,6 +161,6 @@ UJITSO.enabled = true # set the S3 directory manually to the latest published S3 # note: this is done to ensure prior versions of Isaac Sim still use the latest assets [settings] -persistent.isaac.asset_root.default = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.cloud = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.nvidia = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.default = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.cloud = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.nvidia = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" diff --git a/apps/isaaclab.python.kit b/apps/isaaclab.python.kit index 1d3364adf603..282057c0ab00 100644 --- a/apps/isaaclab.python.kit +++ b/apps/isaaclab.python.kit @@ -307,6 +307,6 @@ fabricUseGPUInterop = true # set the S3 directory manually to the latest published S3 # note: this is done to ensure prior versions of Isaac Sim still use the latest assets [settings] -persistent.isaac.asset_root.default = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.cloud = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.nvidia = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.default = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.cloud = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.nvidia = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" diff --git a/apps/isaaclab.python.rendering.kit b/apps/isaaclab.python.rendering.kit index e7ed1d96e105..08982f9b4958 100644 --- a/apps/isaaclab.python.rendering.kit +++ b/apps/isaaclab.python.rendering.kit @@ -144,6 +144,6 @@ UJITSO.enabled = true # set the S3 directory manually to the latest published S3 # note: this is done to ensure prior versions of Isaac Sim still use the latest assets [settings] -persistent.isaac.asset_root.default = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.cloud = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.nvidia = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.default = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.cloud = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.nvidia = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" diff --git a/apps/isaaclab.python.xr.openxr.headless.kit b/apps/isaaclab.python.xr.openxr.headless.kit index 53b6002eacb7..293dd55dfab4 100644 --- a/apps/isaaclab.python.xr.openxr.headless.kit +++ b/apps/isaaclab.python.xr.openxr.headless.kit @@ -71,6 +71,6 @@ UJITSO.geometry = true UJITSO.enabled = true [settings] -persistent.isaac.asset_root.default = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.cloud = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.nvidia = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.default = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.cloud = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.nvidia = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" diff --git a/apps/isaaclab.python.xr.openxr.kit b/apps/isaaclab.python.xr.openxr.kit index e9e72858a39d..6248484e58b0 100644 --- a/apps/isaaclab.python.xr.openxr.kit +++ b/apps/isaaclab.python.xr.openxr.kit @@ -98,6 +98,6 @@ UJITSO.enabled = true # set the S3 directory manually to the latest published S3 # note: this is done to ensure prior versions of Isaac Sim still use the latest assets [settings] -persistent.isaac.asset_root.default = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.cloud = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" -persistent.isaac.asset_root.nvidia = "https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.default = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.cloud = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" +persistent.isaac.asset_root.nvidia = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0" diff --git a/docs/_extensions/isaaclab_docs.py b/docs/_extensions/isaaclab_docs.py index a534009d63a7..e2aa1648c951 100644 --- a/docs/_extensions/isaaclab_docs.py +++ b/docs/_extensions/isaaclab_docs.py @@ -160,7 +160,7 @@ def _quickstart_isaacsim(branch: str, platform: str) -> str: uv venv --python 3.12 --seed env_isaaclab source env_isaaclab/bin/activate uv pip install --upgrade pip - uv pip install "isaacsim[all,extscache]==6.0.0" \\ + uv pip install "isaacsim[all,extscache]==6.0.0.1" \\ --extra-index-url https://pypi.nvidia.com \\ --index-strategy unsafe-best-match --prerelease=allow uv pip install -U torch==2.10.0 torchvision==0.25.0 \\ @@ -178,7 +178,7 @@ def _quickstart_isaacsim(branch: str, platform: str) -> str: uv venv --python 3.12 --seed env_isaaclab env_isaaclab\\Scripts\\activate uv pip install --upgrade pip - uv pip install "isaacsim[all,extscache]==6.0.0" ^ + uv pip install "isaacsim[all,extscache]==6.0.0.1" ^ --extra-index-url https://pypi.nvidia.com ^ --index-strategy unsafe-best-match --prerelease=allow uv pip install -U torch==2.10.0 torchvision==0.25.0 ^ diff --git a/docs/source/overview/core-concepts/physical-backends/newton/installation.rst b/docs/source/overview/core-concepts/physical-backends/newton/installation.rst index 66bc9b9ea373..8a49b781fb91 100644 --- a/docs/source/overview/core-concepts/physical-backends/newton/installation.rst +++ b/docs/source/overview/core-concepts/physical-backends/newton/installation.rst @@ -53,7 +53,7 @@ Ensure pip is up to date: .. code-block:: bash - uv pip install "isaacsim[all,extscache]==6.0.0" --extra-index-url https://pypi.nvidia.com --index-strategy unsafe-best-match --prerelease=allow + uv pip install "isaacsim[all,extscache]==6.0.0.1" --extra-index-url https://pypi.nvidia.com --index-strategy unsafe-best-match --prerelease=allow Install the correct version of torch and torchvision: diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index 03526aba4bd1..bf6656e0dbed 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -484,10 +484,12 @@ Environments based on legged locomotion tasks. +------------------------------+----------------------------------------------+------------------------------------------------------------------------------+------------------------------+ | |velocity-flat-anymal-c| | |velocity-flat-anymal-c-link| | Track a velocity command on flat terrain with the Anymal C robot | **physics=** ``physx``, | | | | | ``newton_mjwarp`` | + | | | | (Manager-based only) | | | |velocity-flat-anymal-c-direct-link| | | | +------------------------------+----------------------------------------------+------------------------------------------------------------------------------+------------------------------+ | |velocity-rough-anymal-c| | |velocity-rough-anymal-c-link| | Track a velocity command on rough terrain with the Anymal C robot | **physics=** ``physx``, | | | | | ``newton_mjwarp`` | + | | | | (Manager-based only) | | | |velocity-rough-anymal-c-direct-link| | | | +------------------------------+----------------------------------------------+------------------------------------------------------------------------------+------------------------------+ | |velocity-flat-anymal-d| | |velocity-flat-anymal-d-link| | Track a velocity command on flat terrain with the Anymal D robot | **physics=** ``physx``, | diff --git a/docs/source/overview/imitation-learning/humanoids_imitation.rst b/docs/source/overview/imitation-learning/humanoids_imitation.rst index 623e60079087..2aa738354f16 100644 --- a/docs/source/overview/imitation-learning/humanoids_imitation.rst +++ b/docs/source/overview/imitation-learning/humanoids_imitation.rst @@ -162,7 +162,7 @@ Generate the dataset ^^^^^^^^^^^^^^^^^^^^ If you skipped the prior collection and annotation step, download the pre-recorded annotated dataset ``dataset_annotated_gr1.hdf5`` from -here: `[Annotated GR1 Dataset] `_. +here: `[Annotated GR1 Dataset] `_. Place the file under ``IsaacLab/datasets`` and run the following command to generate a new dataset with 1000 demonstrations. .. code:: bash @@ -250,7 +250,7 @@ Demo 2: Visuomotor Policy for a Humanoid Robot Download the Dataset ^^^^^^^^^^^^^^^^^^^^ -Download the pre-generated dataset from `here `__ and place it under ``IsaacLab/datasets/generated_dataset_gr1_nut_pouring.hdf5`` +Download the pre-generated dataset from `here `__ and place it under ``IsaacLab/datasets/generated_dataset_gr1_nut_pouring.hdf5`` (**Note: The dataset size is approximately 15GB**). The dataset contains 1000 demonstrations of a humanoid robot performing a pouring/placing task that was generated using Isaac Lab Mimic for the ``Isaac-NutPour-GR1T2-Pink-IK-Abs-Mimic-v0`` task. @@ -467,7 +467,7 @@ Follow the same data collection, annotation, and generation process as demonstra If you skipped the prior collection and annotation step, download the pre-recorded annotated dataset ``dataset_annotated_g1_locomanip.hdf5`` from -here: `[Annotated G1 Dataset] `_. +here: `[Annotated G1 Dataset] `_. Place the file under ``IsaacLab/datasets`` and run the following command to generate a new dataset with 1000 demonstrations. .. code:: bash diff --git a/docs/source/overview/imitation-learning/skillgen.rst b/docs/source/overview/imitation-learning/skillgen.rst index 63b132f7969f..085a65c54109 100644 --- a/docs/source/overview/imitation-learning/skillgen.rst +++ b/docs/source/overview/imitation-learning/skillgen.rst @@ -135,7 +135,7 @@ The dataset contains: Download and Setup ^^^^^^^^^^^^^^^^^^ -1. Download the pre-annotated dataset by clicking `here `__. +1. Download the pre-annotated dataset by clicking `here `__. 2. Prepare the datasets directory and move the downloaded file: diff --git a/docs/source/overview/imitation-learning/teleop_imitation.rst b/docs/source/overview/imitation-learning/teleop_imitation.rst index 3b5bfa6af04f..27c682385cf1 100644 --- a/docs/source/overview/imitation-learning/teleop_imitation.rst +++ b/docs/source/overview/imitation-learning/teleop_imitation.rst @@ -299,7 +299,7 @@ Step 2: Synthetic Data Generation using Isaac Lab Mimic ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ We provide a pre-recorded HDF5 dataset containing 10 human demonstrations for the cube stacking task -here: `[Cube Stacking Human Dataset] `__. +here: `[Cube Stacking Human Dataset] `__. If you skipped :ref:`Step 1: Human Data Collection `, you can download this dataset and use it in the remaining tutorial steps. Place the dataset in the ``IsaacLab/datasets`` folder. You may need to create the folder if you skipped Step 1 and diff --git a/docs/source/setup/installation/isaaclab_pip_installation.rst b/docs/source/setup/installation/isaaclab_pip_installation.rst index f482f7bfbb5d..4da9ee305ee3 100644 --- a/docs/source/setup/installation/isaaclab_pip_installation.rst +++ b/docs/source/setup/installation/isaaclab_pip_installation.rst @@ -30,7 +30,7 @@ pip extras include: * - Extra - What it installs * - ``isaacsim`` - - Isaac Sim (``isaacsim[all,extscache]==6.0.0.*``) from `pypi.nvidia.com `_ + - Isaac Sim (``isaacsim[all,extscache]==6.0.0.1``) from `pypi.nvidia.com `_ * - ``all`` - RL frameworks (SB3, SKRL, RL-Games, RSL-RL). Combine with ``isaacsim`` for a full install. diff --git a/docs/source/setup/installation/pip_installation.rst b/docs/source/setup/installation/pip_installation.rst index defaab955016..6b324b2cabbf 100644 --- a/docs/source/setup/installation/pip_installation.rst +++ b/docs/source/setup/installation/pip_installation.rst @@ -51,7 +51,7 @@ Installing dependencies .. code-block:: bash - uv pip install "isaacsim[all,extscache]==6.0.0" --extra-index-url https://pypi.nvidia.com --index-strategy unsafe-best-match --prerelease=allow + uv pip install "isaacsim[all,extscache]==6.0.0.1" --extra-index-url https://pypi.nvidia.com --index-strategy unsafe-best-match --prerelease=allow - Install a CUDA-enabled PyTorch build that matches your system architecture: diff --git a/scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py b/scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py index 84d1655ca78e..3b11d10e1397 100644 --- a/scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py +++ b/scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py @@ -33,7 +33,6 @@ import isaaclab_tasks_experimental # noqa: F401 from isaaclab_tasks.utils import ( add_launcher_args, - fold_preset_tokens, launch_simulation, resolve_task_config, setup_preset_cli, @@ -122,7 +121,7 @@ def _resolve_task(args_cli: argparse.Namespace) -> str: add_launcher_args(parser) args_cli, hydra_args = setup_preset_cli(parser) args_cli.task = _resolve_task(args_cli) -sys.argv = [sys.argv[0]] + fold_preset_tokens(hydra_args) +sys.argv = [sys.argv[0]] + hydra_args def main(): diff --git a/source/isaaclab_newton/pyproject.toml b/source/isaaclab_newton/pyproject.toml index 5fc4f472fec0..3a2c575f91cd 100644 --- a/source/isaaclab_newton/pyproject.toml +++ b/source/isaaclab_newton/pyproject.toml @@ -28,7 +28,7 @@ Repository = "https://github.com/isaac-sim/IsaacLab" all = [ "prettytable>=3.3.0", "PyOpenGL-accelerate>=3.1.0", - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", ] [tool.setuptools] diff --git a/source/isaaclab_physx/pyproject.toml b/source/isaaclab_physx/pyproject.toml index 4641533578b7..608074911f4e 100644 --- a/source/isaaclab_physx/pyproject.toml +++ b/source/isaaclab_physx/pyproject.toml @@ -26,7 +26,7 @@ Repository = "https://github.com/isaac-sim/IsaacLab" [project.optional-dependencies] newton = [ - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", ] [tool.setuptools] diff --git a/source/isaaclab_visualizers/pyproject.toml b/source/isaaclab_visualizers/pyproject.toml index 14cb7267b34c..317e26d29810 100644 --- a/source/isaaclab_visualizers/pyproject.toml +++ b/source/isaaclab_visualizers/pyproject.toml @@ -29,23 +29,23 @@ Repository = "https://github.com/isaac-sim/IsaacLab" kit = [] newton = [ "warp-lang", - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", "PyOpenGL-accelerate", "imgui-bundle>=1.92.5", "typing-extensions>=4.15.0", ] rerun = [ - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", "rerun-sdk>=0.29.0", "pyarrow==22.0.0", ] viser = [ - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", "viser>=1.0.16", ] all = [ "imgui-bundle>=1.92.5", - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", "PyOpenGL-accelerate", # Match rerun-sdk's supported Arrow stack and avoid resolver drift across environments. "pyarrow==22.0.0", diff --git a/tools/wheel_builder/res/python_packages.toml b/tools/wheel_builder/res/python_packages.toml index 998dc8a05de3..f93f75030a5d 100644 --- a/tools/wheel_builder/res/python_packages.toml +++ b/tools/wheel_builder/res/python_packages.toml @@ -39,7 +39,7 @@ pyproject.dependencies.all = [ "flaky", "packaging", # visualizers - "imgui-bundle==1.92.4", + "imgui-bundle==1.92.601", "rerun-sdk>=0.29.0", "pyarrow==22.0.0", # viser is intentionally not a base dep: viser>=1.0.16 pulls websockets>=13.1, @@ -82,13 +82,13 @@ pyproject.dependencies.all = [ ] pyproject.optional-dependencies.all = [ # Isaac Sim - { "isaacsim" = ["isaacsim[all,extscache]==6.0.0.*"] }, + { "isaacsim" = ["isaacsim[all,extscache]==6.0.0.1"] }, # ================================================================================ # https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab_newton/setup.py # ================================================================================ { "newton" = [ "warp-lang==1.13.0", - "newton[sim] @ git+https://github.com/newton-physics/newton.git@v1.2.1rc2", + "newton[sim]==1.2.1", "PyOpenGL-accelerate==3.1.10" ] }, # ================================================================================ From 9996a0861be64a9f3dcfc33f0bce16751a6a12c2 Mon Sep 17 00:00:00 2001 From: Mustafa H <34825877+StafaH@users.noreply.github.com> Date: Sun, 7 Jun 2026 05:24:59 -0400 Subject: [PATCH 10/40] Fix multidoc build (#6012) # Description Fix the multi-doc build, the new -j argument is not getting parsed correctly. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Makefile b/docs/Makefile index 58dde84885a2..82f4c708b7f0 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -10,7 +10,7 @@ BUILDDIR = _build .PHONY: multi-docs multi-docs: - @sphinx-multiversion "$(SOURCEDIR)" "$(BUILDDIR)" -j auto $(SPHINXOPTS) + @sphinx-multiversion "$(SOURCEDIR)" "$(BUILDDIR)" --jobs=auto $(SPHINXOPTS) @cp _redirect/index.html $(BUILDDIR)/index.html .PHONY: current-docs From 9de9c44d16fa6d54994816f6f8d8e80534d156fd Mon Sep 17 00:00:00 2001 From: ooctipus Date: Sun, 7 Jun 2026 04:29:15 -0700 Subject: [PATCH 11/40] Fix local MDL texture dependency retrieval (#5978) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Fixes local mirroring of remote USD assets that reference MDL materials with texture defaults. The previous recursive download path discovered USD dependencies, including MDL files, but did not discover texture resources referenced from inside those MDL files. When the mirrored MDL files were loaded locally, RTX attempted to resolve their relative texture defaults from the local mirror and emitted unresolved texture warnings. This generalizes the dependency discovery helper so the download loop asks for dependencies from each mirrored asset. USD files continue to use OpenUSD dependency discovery, and MDL files now contribute quoted texture resource paths for the same mirror-download path. Fixes # N/A ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots N/A ## Testing - `PYTHONPATH=/tmp/isaaclab-pr-mdl/source/isaaclab python -m pytest source/isaaclab/test/utils/test_assets.py -q` - `4 passed` - Re-ran the locomanipulation scene repro with a fresh `TMPDIR` asset mirror. - `texture_warnings 0` - PackingTable MDL textures were downloaded into the fresh mirror. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- scripts/benchmarks/startup_whitelist.yaml | 2 +- .../fix-mdl-texture-dependencies.rst | 4 ++ source/isaaclab/isaaclab/utils/assets.py | 69 +++++++++++-------- source/isaaclab/test/utils/test_assets.py | 35 ++++++++++ .../fix-newton-close-site-leak.rst | 4 ++ .../isaaclab_newton/physics/newton_manager.py | 2 +- .../frame_transformer/frame_transformer.py | 6 +- .../isaaclab_newton/sensors/imu/imu.py | 8 +-- 8 files changed, 94 insertions(+), 36 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst create mode 100644 source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst diff --git a/scripts/benchmarks/startup_whitelist.yaml b/scripts/benchmarks/startup_whitelist.yaml index 121718d36b40..3aef4a729723 100644 --- a/scripts/benchmarks/startup_whitelist.yaml +++ b/scripts/benchmarks/startup_whitelist.yaml @@ -14,7 +14,7 @@ env_creation: - "isaaclab_physx.cloner.*:attach_end_fn" - "isaaclab.scene.*:_init_scene" - "isaaclab.envs.mdp.observations:*" - - "isaaclab.utils.assets:_find_usd_dependencies" + - "isaaclab.utils.assets:_find_asset_dependencies" first_step: - "isaaclab.envs.mdp.rewards:*" diff --git a/source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst b/source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst new file mode 100644 index 000000000000..e42b37ff69a6 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed remote asset mirroring to include textures referenced by downloaded MDL materials. diff --git a/source/isaaclab/isaaclab/utils/assets.py b/source/isaaclab/isaaclab/utils/assets.py index 79ccdefced4a..603df8b2aa43 100644 --- a/source/isaaclab/isaaclab/utils/assets.py +++ b/source/isaaclab/isaaclab/utils/assets.py @@ -25,6 +25,9 @@ logger = logging.getLogger(__name__) _UDIM_RE = re.compile(r"", re.IGNORECASE) +_USD_EXTENSIONS = {".usd", ".usda", ".usdc", ".usdz"} +_MDL_RESOURCE_RE = re.compile(r'"([^"\\]*(?:\\.[^"\\]*)*)"|/\*.*?\*/|//[^\r\n]*', re.DOTALL) +_MDL_TEXTURE_RE = re.compile(r"\.(?:bmp|dds|exr|hdr|ies|jpe?g|ktx2?|png|tga|tiff?|tx)(?:[?#].*)?$", re.IGNORECASE) def _parse_kit_asset_root() -> str: @@ -142,21 +145,23 @@ def retrieve_file_path(path: str, download_dir: str | None = None, force_downloa target_path = os.path.join(download_dir, cur_rel) os.makedirs(os.path.dirname(target_path), exist_ok=True) + is_root_asset = local_root is None if not os.path.isfile(target_path) or force_download: result = omni.client.copy(cur_url, target_path, omni.client.CopyBehavior.OVERWRITE) - if result != omni.client.Result.OK and force_download: - raise RuntimeError(f"Unable to copy file: '{cur_url}'. Is the Nucleus Server running?") + if result != omni.client.Result.OK: + if force_download or is_root_asset: + raise RuntimeError(f"Unable to copy file: '{cur_url}'. Is the Nucleus Server running?") + logger.debug("Skipping unavailable dependency: %s", cur_url) + continue if local_root is None: local_root = target_path - # recurse into USD dependencies (sublayers, references, payloads, textures, etc.) - suffix = os.path.splitext(target_path)[1].lower() - if suffix in {".usd", ".usda", ".usdc", ".usdz"}: - for ref in _find_usd_dependencies(target_path): - ref_url = _resolve_reference_url(cur_url, ref) - if ref_url and ref_url not in visited: - to_visit.append(ref_url) + # recurse into dependencies (USD references, payloads, MDL textures, etc.) + for ref in _find_asset_dependencies(target_path): + ref_url = _resolve_reference_url(cur_url, ref) + if ref_url and ref_url not in visited: + to_visit.append(ref_url) return os.path.abspath(local_root) else: @@ -189,40 +194,50 @@ def read_file(path: str) -> io.BytesIO: raise FileNotFoundError(f"Unable to find the file: {path}") -def _find_usd_dependencies(local_usd_path: str) -> set[str]: - """Use UsdUtils to collect all asset dependencies from a USD file. +def _find_asset_dependencies(local_asset_path: str) -> set[str]: + """Collect external asset dependencies from a local asset file. - This uses :func:`UsdUtils.ComputeAllDependencies` — the same approach as - ``isaacsim.storage.native`` — to discover sublayers, references, payloads, - and non-layer assets (textures, etc.) without maintaining a hardcoded list - of file extensions. - - Args: - local_usd_path: Path to a local USD file. - - Returns: - Set of asset path strings as they appear in the USD layer (unresolved). + USD layers are parsed with OpenUSD. MDL files are scanned for quoted texture + resources because those references are resolved later by the MDL compiler and + are not reported by USD dependency discovery. """ + suffix = os.path.splitext(local_asset_path)[1].lower() + + if suffix == ".mdl": + try: + with open(local_asset_path, encoding="utf-8") as f: + source = f.read() + except OSError as e: + logger.warning("Failed to open MDL file: %s (%s)", local_asset_path, e) + return set() + + refs = set() + for match in _MDL_RESOURCE_RE.finditer(source): + ref = match.group(1) + if ref and _MDL_TEXTURE_RE.search(ref.strip()): + refs.add(ref.strip()) + return refs + + if suffix not in _USD_EXTENSIONS: + return set() + from pxr import Sdf, UsdUtils # noqa: PLC0415 try: - layer = Sdf.Layer.FindOrOpen(local_usd_path) + layer = Sdf.Layer.FindOrOpen(local_asset_path) except Exception: - logger.warning("Failed to open USD layer: %s", local_usd_path, exc_info=True) + logger.warning("Failed to open USD layer: %s", local_asset_path, exc_info=True) return set() if layer is None: return set() - # Collect every asset path referenced from this layer. - # UsdUtils.ModifyAssetPaths walks sublayers, references, payloads, - # variant selections, and attribute values — exactly the set we need. refs: set[str] = set() def _collect(path: str) -> str: if path: refs.add(path) - return path # return unchanged — we are only reading, not modifying + return path UsdUtils.ModifyAssetPaths(layer, _collect) diff --git a/source/isaaclab/test/utils/test_assets.py b/source/isaaclab/test/utils/test_assets.py index 147b8c04c831..d4019246e637 100644 --- a/source/isaaclab/test/utils/test_assets.py +++ b/source/isaaclab/test/utils/test_assets.py @@ -29,3 +29,38 @@ def test_check_file_path_invalid(): usd_path = f"{assets_utils.ISAACLAB_NUCLEUS_DIR}/Robots/FrankaEmika/panda_xyz.usd" # check file path assert assets_utils.check_file_path(usd_path) == 0 + + +def test_find_asset_dependencies_collects_mdl_texture_resources(tmp_path): + """Test collecting texture resources from quoted MDL strings.""" + mdl_path = tmp_path / "material.mdl" + mdl_path.write_text( + """ + export material Example(*) = OmniPBR( + diffuse_texture: texture_2d("./textures/Albedo.png", ::tex::gamma_srgb), + normalmap_texture: texture_2d("../shared/Normal.EXR", ::tex::gamma_linear), + ORM_texture: texture_2d("https://example.com/materials/orm..png", ::tex::gamma_linear), + roughness_texture: texture_2d("omniverse://server/Library/roughness.tx", ::tex::gamma_linear), + ignored_label: "not_a_texture", + empty_texture: texture_2d() + ); + // texture_2d("./textures/commented_line.png") + /* texture_2d("./textures/commented_block.png") */ + """, + encoding="utf-8", + ) + + assert assets_utils._find_asset_dependencies(str(mdl_path)) == { + "./textures/Albedo.png", + "../shared/Normal.EXR", + "https://example.com/materials/orm..png", + "omniverse://server/Library/roughness.tx", + } + + +def test_find_asset_dependencies_missing_mdl_does_not_log_traceback(tmp_path, caplog): + """Test unavailable MDL dependencies do not emit tracebacks in training logs.""" + missing_mdl = tmp_path / "missing.mdl" + + assert assets_utils._find_asset_dependencies(str(missing_mdl)) == set() + assert "Traceback (most recent call last):" not in caplog.text diff --git a/source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst b/source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst new file mode 100644 index 000000000000..88b9a9d129ba --- /dev/null +++ b/source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed stale Newton sensor site registrations leaking across simulation context teardown. diff --git a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py index 41aea04368f4..59464374e1f9 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py +++ b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py @@ -608,8 +608,8 @@ def step(cls) -> None: @classmethod def close(cls) -> None: """Clean up Newton physics resources.""" - cls.clear() super().close() + cls.clear() @classmethod def get_scene_data_backend(cls) -> SceneDataBackend | None: diff --git a/source/isaaclab_newton/isaaclab_newton/sensors/frame_transformer/frame_transformer.py b/source/isaaclab_newton/isaaclab_newton/sensors/frame_transformer/frame_transformer.py index e9150b63174b..2037e595438f 100644 --- a/source/isaaclab_newton/isaaclab_newton/sensors/frame_transformer/frame_transformer.py +++ b/source/isaaclab_newton/isaaclab_newton/sensors/frame_transformer/frame_transformer.py @@ -333,9 +333,9 @@ def _update_buffers_impl(self, env_mask: wp.array): def _invalidate_initialize_callback(self, event): """Clears references to the native sensor and re-registers sites. - ``NewtonManager.close()`` calls ``clear()`` before dispatching ``STOP``, - so ``_cl_pending_sites`` is already empty when this callback fires. - Re-registering here ensures sites survive a close/reinit cycle. + Re-registering here ensures sites survive a non-teardown stop/reinit cycle. + During ``NewtonManager.close()``, Newton state is cleared after ``STOP`` so + stale registrations from old sensors cannot leak into the next context. """ super()._invalidate_initialize_callback(event) self._newton_transforms = None diff --git a/source/isaaclab_newton/isaaclab_newton/sensors/imu/imu.py b/source/isaaclab_newton/isaaclab_newton/sensors/imu/imu.py index b76b913800c8..618b33dca8d8 100644 --- a/source/isaaclab_newton/isaaclab_newton/sensors/imu/imu.py +++ b/source/isaaclab_newton/isaaclab_newton/sensors/imu/imu.py @@ -171,10 +171,10 @@ def _update_buffers_impl(self, env_mask: wp.array): def _invalidate_initialize_callback(self, event): """Clears references to the native Newton sensor and re-registers site/attributes. - ``NewtonManager.close()`` calls ``clear()`` before dispatching ``STOP``, - so ``_cl_pending_sites`` and ``_pending_extended_state_attributes`` are - already empty when this callback fires. Re-registering here ensures the - site and ``body_qdd`` attribute survive a close/reinit cycle. + Re-registering here ensures the site and ``body_qdd`` attribute survive a + non-teardown stop/reinit cycle. During ``NewtonManager.close()``, Newton + state is cleared after ``STOP`` so stale registrations from old sensors + cannot leak into the next context. """ super()._invalidate_initialize_callback(event) self._newton_sensor = None From 0a0dc1be475604a1e0ab6aecfc260a7b914ac591 Mon Sep 17 00:00:00 2001 From: YizeWang <37894497+YizeWang@users.noreply.github.com> Date: Sun, 7 Jun 2026 20:10:53 +0800 Subject: [PATCH 12/40] Support Multi-Backend for Demo Scripts (#5938) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description This PR updates the demo scripts to support running across the default KitViz/PhysX path and NewtonViz/Newton-MJWarp backend combinations. The affected demos now use consistent CLI parsing, import ordering, usage comments, default Kit visualizer behavior, and visualizer-aware simulation loops. It also tunes selected Newton MJWarp solver parameters for demos that need more stable articulation/contact behavior, avoids resolving `InteractiveScene` before simulation launch in `bin_packing.py`, and adds Newton visualizer support for `SimulationContext.set_camera_view()`. **Dependencies** - https://github.com/isaac-sim/IsaacLab/pull/5826 - https://github.com/isaac-sim/IsaacLab/pull/5892 ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) - Documentation update ## Validation Validated the demo matrix for: - `scripts/demos/arl_robot_1.py` - `scripts/demos/arms.py` - `scripts/demos/bin_packing.py` - `scripts/demos/bipeds.py` - `scripts/demos/hands.py` - `scripts/demos/quadcopter.py` - `scripts/demos/quadrupeds.py` with: - default Kit visualizer + PhysX - Newton visualizer + PhysX - default Kit visualizer + Newton MJWarp - Newton visualizer + Newton MJWarp ## Screenshots arms bin_packing bipeds hands_fixed quadcopter quadrupeds ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Signed-off-by: Yize Wang Co-authored-by: Yize Wang --- scripts/demos/arms.py | 116 ++++++----- scripts/demos/bin_packing.py | 100 ++++++---- scripts/demos/bipeds.py | 109 ++++++----- scripts/demos/hands.py | 97 ++++++---- scripts/demos/quadcopter.py | 182 +++++++++--------- scripts/demos/quadrupeds.py | 55 +++--- .../yizew-support-multi-backends.rst | 14 ++ .../isaaclab/scene/interactive_scene_cfg.py | 12 ++ .../isaaclab/sim/simulation_context.py | 4 + .../yizew-support-multi-backends.rst | 6 + .../newton/newton_visualizer.py | 14 ++ 11 files changed, 414 insertions(+), 295 deletions(-) create mode 100644 source/isaaclab/changelog.d/yizew-support-multi-backends.rst create mode 100644 source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst diff --git a/scripts/demos/arms.py b/scripts/demos/arms.py index b08686a8e52c..7575ddb81a52 100644 --- a/scripts/demos/arms.py +++ b/scripts/demos/arms.py @@ -8,53 +8,55 @@ .. code-block:: bash - # Usage + # Usage with default PhysX physics and default kit visualizer. ./isaaclab.sh -p scripts/demos/arms.py + # Usage with Newton visualizer and default PhysX physics. + ./isaaclab.sh -p scripts/demos/arms.py --visualizer newton + + # Usage with Newton (MJWarp) physics and default kit visualizer. + ./isaaclab.sh -p scripts/demos/arms.py --physics newton_mjwarp + + # Usage with Newton visualizer and Newton (MJWarp) physics. + ./isaaclab.sh -p scripts/demos/arms.py --visualizer newton --physics newton_mjwarp + """ -"""Launch Isaac Sim Simulator first.""" +"""Parse CLI first so we can decide whether to launch Isaac Sim Kit.""" import argparse +from typing import TYPE_CHECKING -from isaaclab.app import AppLauncher +from isaaclab.app import add_launcher_args, launch_simulation -# add argparse arguments -parser = argparse.ArgumentParser(description="This script demonstrates different single-arm manipulators.") -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# demos should open Kit visualizer by default +parser = argparse.ArgumentParser( + description="This script demonstrates different single-arm manipulators.", + conflict_handler="resolve", +) +parser.add_argument("--physics", default="physx", choices=["physx", "newton_mjwarp"], help="Physics backend.") +add_launcher_args(parser) parser.set_defaults(visualizer=["kit"]) -# parse the arguments args_cli = parser.parse_args() -# launch omniverse app -app_launcher = AppLauncher(args_cli) -simulation_app = app_launcher.app - -"""Rest everything follows.""" - import numpy as np import torch import isaaclab.sim as sim_utils -from isaaclab.assets import Articulation -from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR ## # Pre-defined configs ## -# isort: off -from isaaclab_assets import ( - FRANKA_PANDA_CFG, - UR10_CFG, - KINOVA_JACO2_N7S300_CFG, - KINOVA_JACO2_N6S300_CFG, - KINOVA_GEN3_N7_CFG, - SAWYER_CFG, -) +from isaaclab.physics import PhysicsCfg +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR + +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg # isort:skip +from isaaclab_assets.robots.franka import FRANKA_PANDA_CFG # isort:skip +from isaaclab_assets.robots.kinova import KINOVA_GEN3_N7_CFG, KINOVA_JACO2_N6S300_CFG, KINOVA_JACO2_N7S300_CFG # isort:skip +from isaaclab_assets.robots.sawyer import SAWYER_CFG # isort:skip +from isaaclab_assets.robots.universal_robots import UR10_CFG # isort:skip -# isort: on +if TYPE_CHECKING: + from isaaclab.assets import Articulation def define_origins(num_origins: int, spacing: float) -> list[list[float]]: @@ -93,7 +95,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot franka_arm_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/Origin1/Robot") franka_arm_cfg.init_state.pos = (0.0, 0.0, 1.05) - franka_panda = Articulation(cfg=franka_arm_cfg) + franka_panda = franka_arm_cfg.class_type(franka_arm_cfg) # Origin 2 with UR10 sim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1]) @@ -105,7 +107,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot ur10_cfg = UR10_CFG.replace(prim_path="/World/Origin2/Robot") ur10_cfg.init_state.pos = (0.0, 0.0, 1.03) - ur10 = Articulation(cfg=ur10_cfg) + ur10 = ur10_cfg.class_type(ur10_cfg) # Origin 3 with Kinova JACO2 (7-Dof) arm sim_utils.create_prim("/World/Origin3", "Xform", translation=origins[2]) @@ -115,7 +117,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot kinova_arm_cfg = KINOVA_JACO2_N7S300_CFG.replace(prim_path="/World/Origin3/Robot") kinova_arm_cfg.init_state.pos = (0.0, 0.0, 0.8) - kinova_j2n7s300 = Articulation(cfg=kinova_arm_cfg) + kinova_j2n7s300 = kinova_arm_cfg.class_type(kinova_arm_cfg) # Origin 4 with Kinova JACO2 (6-Dof) arm sim_utils.create_prim("/World/Origin4", "Xform", translation=origins[3]) @@ -125,7 +127,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot kinova_arm_cfg = KINOVA_JACO2_N6S300_CFG.replace(prim_path="/World/Origin4/Robot") kinova_arm_cfg.init_state.pos = (0.0, 0.0, 0.8) - kinova_j2n6s300 = Articulation(cfg=kinova_arm_cfg) + kinova_j2n6s300 = kinova_arm_cfg.class_type(kinova_arm_cfg) # Origin 5 with Sawyer sim_utils.create_prim("/World/Origin5", "Xform", translation=origins[4]) @@ -135,7 +137,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot kinova_arm_cfg = KINOVA_GEN3_N7_CFG.replace(prim_path="/World/Origin5/Robot") kinova_arm_cfg.init_state.pos = (0.0, 0.0, 1.05) - kinova_gen3n7 = Articulation(cfg=kinova_arm_cfg) + kinova_gen3n7 = kinova_arm_cfg.class_type(kinova_arm_cfg) # Origin 6 with Kinova Gen3 (7-Dof) arm sim_utils.create_prim("/World/Origin6", "Xform", translation=origins[5]) @@ -147,7 +149,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot sawyer_arm_cfg = SAWYER_CFG.replace(prim_path="/World/Origin6/Robot") sawyer_arm_cfg.init_state.pos = (0.0, 0.0, 1.03) - sawyer = Articulation(cfg=sawyer_arm_cfg) + sawyer = sawyer_arm_cfg.class_type(sawyer_arm_cfg) # return the scene information scene_entities = { @@ -161,14 +163,14 @@ def design_scene() -> tuple[dict, list[list[float]]]: return scene_entities, origins -def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor): +def run_simulator(sim: "sim_utils.SimulationContext", entities: dict[str, "Articulation"], origins: torch.Tensor): """Runs the simulation loop.""" # Define simulation stepping sim_dt = sim.get_physics_dt() sim_time = 0.0 count = 0 - # Simulate physics - while simulation_app.is_running(): + # Step while a visualizer window is still open (or none exist, e.g. headless); works for kit and newton. + while sim.is_headless_or_exist_active_visualizer(): # reset if count % 200 == 0: # reset counters @@ -214,24 +216,34 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula def main(): """Main function.""" - # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device) - sim = sim_utils.SimulationContext(sim_cfg) - # Set main camera - sim.set_camera_view([3.5, 0.0, 3.2], [0.0, 0.0, 0.5]) - # design scene - scene_entities, scene_origins = design_scene() - scene_origins = torch.tensor(scene_origins, device=sim.device) - # Play the simulator - sim.reset() - # Now we are ready! - print("[INFO]: Setup complete...") - # Run the simulator - run_simulator(sim, scene_entities, scene_origins) + with launch_simulation(cfg=PhysicsCfg(), launcher_args=args_cli) as physics_cfg: + # The default newton mjwarp solver configuration needs to be tuned for these arms. + if isinstance(physics_cfg, NewtonCfg) and isinstance(physics_cfg.solver_cfg, MJWarpSolverCfg): + physics_cfg.solver_cfg.njmax = 70 + physics_cfg.solver_cfg.nconmax = 70 + physics_cfg.solver_cfg.ls_iterations = 40 + physics_cfg.solver_cfg.cone = "elliptic" + physics_cfg.solver_cfg.impratio = 100 + physics_cfg.solver_cfg.ls_parallel = False + physics_cfg.solver_cfg.integrator = "implicitfast" + physics_cfg.num_substeps = 2 + + # Initialize the simulation context + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=physics_cfg) + sim = sim_utils.SimulationContext(sim_cfg) + # Set main camera + sim.set_camera_view([3.5, 0.0, 3.2], [0.0, 0.0, 0.5]) + # design scene + scene_entities, scene_origins = design_scene() + scene_origins = torch.tensor(scene_origins, device=sim.device) + # Play the simulator + sim.reset() + # Now we are ready! + print("[INFO]: Setup complete...") + # Run the simulator + run_simulator(sim, scene_entities, scene_origins) if __name__ == "__main__": # run the main function main() - # close sim app - simulation_app.close() diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index 989c71554285..273f633fecd4 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -13,49 +13,60 @@ .. code-block:: bash - # Usage - ./isaaclab.sh -p scripts/demos/bin_packing.py --num_envs 32 + # Usage with default PhysX physics and default kit visualizer. + ./isaaclab.sh -p scripts/demos/bin_packing.py + + # Usage with Newton visualizer and default PhysX physics. + ./isaaclab.sh -p scripts/demos/bin_packing.py --visualizer newton + + # Usage with Newton (MJWarp) physics and default kit visualizer. + ./isaaclab.sh -p scripts/demos/bin_packing.py --physics newton_mjwarp + + # Usage with Newton visualizer and Newton (MJWarp) physics. + ./isaaclab.sh -p scripts/demos/bin_packing.py --visualizer newton --physics newton_mjwarp """ from __future__ import annotations -"""Launch Isaac Sim Simulator first.""" - +"""Parse CLI first so we can decide whether to launch Isaac Sim Kit.""" import argparse +from typing import TYPE_CHECKING -from isaaclab.app import AppLauncher +from isaaclab.app import add_launcher_args, launch_simulation -# add argparse arguments -parser = argparse.ArgumentParser(description="Demo usage of RigidObjectCollection through bin packing example") +parser = argparse.ArgumentParser( + description="Demo usage of RigidObjectCollection through bin packing example", + conflict_handler="resolve", +) parser.add_argument("--num_envs", type=int, default=16, help="Number of environments to spawn.") -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# demos should open Kit visualizer by default +parser.add_argument("--physics", default="physx", choices=["physx", "newton_mjwarp"], help="Physics backend.") +add_launcher_args(parser) parser.set_defaults(visualizer=["kit"]) -# parse the arguments args_cli = parser.parse_args() -# launch omniverse app -app_launcher = AppLauncher(args_cli) -simulation_app = app_launcher.app - -"""Rest everything follows.""" - import math import torch +## +# Pre-defined configs +## +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg + import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils -from isaaclab.assets import AssetBaseCfg, RigidObjectCfg, RigidObjectCollection, RigidObjectCollectionCfg +from isaaclab.assets import AssetBaseCfg, RigidObjectCfg, RigidObjectCollectionCfg +from isaaclab.physics import PhysicsCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg -from isaaclab.sim import SimulationContext from isaaclab.utils import Timer from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass +if TYPE_CHECKING: + from isaaclab.assets import RigidObjectCollection + ## # Scene Configuration ## @@ -131,7 +142,7 @@ class MultiObjectSceneCfg(InteractiveSceneCfg): # Instantiate four grocery variants per layer and replicate across all layers in each environment. rigid_objects={ f"Object_{label}_Layer{layer}": RigidObjectCfg( - prim_path=f"/World/envs/env_.*/Object_{label}_Layer{layer}", + prim_path=f"/World/envs/env_.*/Groceries/Object_{label}_Layer{layer}", init_state=RigidObjectCfg.InitialStateCfg(pos=(x, y, 0.2 + (layer) * 0.2)), spawn=GROCERIES.get(f"OBJECT_{label}"), ) @@ -263,7 +274,7 @@ def build_grocery_defaults( ## -def run_simulator(sim: SimulationContext, scene: InteractiveScene) -> None: +def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene) -> None: """Runs the simulation loop that coordinates spawn randomization and stepping. Returns: @@ -295,8 +306,8 @@ def run_simulator(sim: SimulationContext, scene: InteractiveScene) -> None: # Precompute a helper mask to toggle objects between active and cached sets. # Precompute XY bounds [[x_min,y_min],[x_max,y_max]] bounds_xy = torch.as_tensor(BIN_XY_BOUND, device=device, dtype=spawn_poses_w.dtype) - # Simulation loop - while simulation_app.is_running(): + # Step while a visualizer window is still open (or none exist, e.g. headless); works for kit and newton. + while sim.is_headless_or_exist_active_visualizer(): # Reset if count % 250 == 0: # reset counter @@ -343,27 +354,32 @@ def main() -> None: Returns: None: The function drives the simulation for its side-effects. """ - # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) - sim = SimulationContext(sim_cfg) - # Set main camera - sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) - - # Design scene - scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=1.0, replicate_physics=True) - with Timer("[INFO] Time to create scene: "): - scene = InteractiveScene(scene_cfg) - - # Play the simulator - sim.reset() - # Now we are ready! - print("[INFO]: Setup complete...") - # Run the simulator - run_simulator(sim, scene) + with launch_simulation(cfg=PhysicsCfg(), launcher_args=args_cli) as physics_cfg: + # The default newton mjwarp solver configuration needs to be tuned for this demo. + if isinstance(physics_cfg, NewtonCfg) and isinstance(physics_cfg.solver_cfg, MJWarpSolverCfg): + physics_cfg.solver_cfg.nconmax = 128 + physics_cfg.solver_cfg.naconmax = 2048 + physics_cfg.solver_cfg.njmax = 512 + + # Load kit helper + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, physics=physics_cfg) + sim = sim_utils.SimulationContext(sim_cfg) + # Set main camera + sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) + + # Design scene + scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=1.0, replicate_physics=True) + with Timer("[INFO] Time to create scene: "): + scene = scene_cfg.class_type(scene_cfg) + + # Play the simulator + sim.reset() + # Now we are ready! + print("[INFO]: Setup complete...") + # Run the simulator + run_simulator(sim, scene) if __name__ == "__main__": # run the main execution main() - # close sim app - simulation_app.close() diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index 68f79db14fcb..36a51e7def2e 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -8,47 +8,54 @@ .. code-block:: bash - # Usage + # Usage with default PhysX physics and default kit visualizer. ./isaaclab.sh -p scripts/demos/bipeds.py + # Usage with Newton visualizer and default PhysX physics. + ./isaaclab.sh -p scripts/demos/bipeds.py --visualizer newton + + # Usage with Newton (MJWarp) physics and default kit visualizer. + ./isaaclab.sh -p scripts/demos/bipeds.py --physics newton_mjwarp + + # Usage with Newton visualizer and Newton (MJWarp) physics. + ./isaaclab.sh -p scripts/demos/bipeds.py --visualizer newton --physics newton_mjwarp + """ -"""Launch Isaac Sim Simulator first.""" +"""Parse CLI first so we can decide whether to launch Isaac Sim Kit.""" import argparse +from typing import TYPE_CHECKING -from isaaclab.app import AppLauncher +from isaaclab.app import add_launcher_args, launch_simulation -# add argparse arguments -parser = argparse.ArgumentParser(description="This script demonstrates how to simulate bipedal robots.") -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# demos should open Kit visualizer by default +parser = argparse.ArgumentParser( + description="This script demonstrates how to simulate bipedal robots.", + conflict_handler="resolve", +) +parser.add_argument("--physics", default="physx", choices=["physx", "newton_mjwarp"], help="Physics backend.") +add_launcher_args(parser) parser.set_defaults(visualizer=["kit"]) -# parse the arguments args_cli = parser.parse_args() -# launch omniverse app -app_launcher = AppLauncher(args_cli) -simulation_app = app_launcher.app - -"""Rest everything follows.""" - import torch import isaaclab.sim as sim_utils -from isaaclab.assets import Articulation -from isaaclab.sim import SimulationContext ## # Pre-defined configs ## +from isaaclab.physics import PhysicsCfg + +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg # isort:skip from isaaclab_assets.robots.cassie import CASSIE_CFG # isort:skip -from isaaclab_assets import H1_CFG # isort:skip -from isaaclab_assets import G1_CFG # isort:skip +from isaaclab_assets.robots.unitree import G1_CFG, H1_CFG # isort:skip +if TYPE_CHECKING: + from isaaclab.assets import Articulation -def design_scene(sim: sim_utils.SimulationContext) -> tuple[list, torch.Tensor]: + +def design_scene(sim: "sim_utils.SimulationContext") -> tuple[list, torch.Tensor]: """Designs the scene.""" # Ground-plane cfg = sim_utils.GroundPlaneCfg() @@ -67,22 +74,25 @@ def design_scene(sim: sim_utils.SimulationContext) -> tuple[list, torch.Tensor]: ).to(device=sim.device) # Robots - cassie = Articulation(CASSIE_CFG.replace(prim_path="/World/Cassie")) - h1 = Articulation(H1_CFG.replace(prim_path="/World/H1")) - g1 = Articulation(G1_CFG.replace(prim_path="/World/G1")) + cassie_cfg = CASSIE_CFG.replace(prim_path="/World/Cassie") + cassie = cassie_cfg.class_type(cassie_cfg) + h1_cfg = H1_CFG.replace(prim_path="/World/H1") + h1 = h1_cfg.class_type(h1_cfg) + g1_cfg = G1_CFG.replace(prim_path="/World/G1") + g1 = g1_cfg.class_type(g1_cfg) robots = [cassie, h1, g1] return robots, origins -def run_simulator(sim: sim_utils.SimulationContext, robots: list[Articulation], origins: torch.Tensor): +def run_simulator(sim: "sim_utils.SimulationContext", robots: list["Articulation"], origins: torch.Tensor): """Runs the simulation loop.""" # Define simulation stepping sim_dt = sim.get_physics_dt() sim_time = 0.0 count = 0 - # Simulate physics - while simulation_app.is_running(): + # Step while a visualizer window is still open (or none exist, e.g. headless); works for kit and newton. + while sim.is_headless_or_exist_active_visualizer(): # reset if count % 200 == 0: # reset counters @@ -120,27 +130,36 @@ def run_simulator(sim: sim_utils.SimulationContext, robots: list[Articulation], def main(): """Main function.""" - # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) - sim = SimulationContext(sim_cfg) - # Set main camera - sim.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) - - # design scene - robots, origins = design_scene(sim) - - # Play the simulator - sim.reset() - - # Now we are ready! - print("[INFO]: Setup complete...") - - # Run the simulator - run_simulator(sim, robots, origins) + with launch_simulation(cfg=PhysicsCfg(), launcher_args=args_cli) as physics_cfg: + # The default newton mjwarp solver configuration needs to be tuned for these bipeds. + if isinstance(physics_cfg, NewtonCfg) and isinstance(physics_cfg.solver_cfg, MJWarpSolverCfg): + physics_cfg.solver_cfg.njmax = 70 + physics_cfg.solver_cfg.nconmax = 70 + physics_cfg.solver_cfg.ls_iterations = 40 + physics_cfg.solver_cfg.cone = "elliptic" + physics_cfg.solver_cfg.impratio = 100 + physics_cfg.solver_cfg.ls_parallel = False + physics_cfg.solver_cfg.integrator = "implicitfast" + physics_cfg.num_substeps = 2 + # Load kit helper + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, physics=physics_cfg) + sim = sim_utils.SimulationContext(sim_cfg) + # Set main camera + sim.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) + + # design scene + robots, origins = design_scene(sim) + + # Play the simulator + sim.reset() + + # Now we are ready! + print("[INFO]: Setup complete...") + + # Run the simulator + run_simulator(sim, robots, origins) if __name__ == "__main__": # run the main function main() - # close sim app - simulation_app.close() diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index 4b9a12d7b433..9523d5fcde26 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -8,43 +8,53 @@ .. code-block:: bash - # Usage + # Usage with default PhysX physics and default kit visualizer. ./isaaclab.sh -p scripts/demos/hands.py + # Usage with Newton visualizer and default PhysX physics. + ./isaaclab.sh -p scripts/demos/hands.py --visualizer newton + + # Usage with Newton (MJWarp) physics and default kit visualizer. + ./isaaclab.sh -p scripts/demos/hands.py --physics newton_mjwarp + + # Usage with Newton visualizer and Newton (MJWarp) physics. + ./isaaclab.sh -p scripts/demos/hands.py --visualizer newton --physics newton_mjwarp + """ -"""Launch Isaac Sim Simulator first.""" +"""Parse CLI first so we can decide whether to launch Isaac Sim Kit.""" import argparse +from typing import TYPE_CHECKING -from isaaclab.app import AppLauncher +from isaaclab.app import add_launcher_args, launch_simulation -# add argparse arguments -parser = argparse.ArgumentParser(description="This script demonstrates different dexterous hands.") -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# demos should open Kit visualizer by default +parser = argparse.ArgumentParser( + description="This script demonstrates different dexterous hands.", + conflict_handler="resolve", +) +parser.add_argument("--physics", default="physx", choices=["physx", "newton_mjwarp"], help="Physics backend.") +add_launcher_args(parser) parser.set_defaults(visualizer=["kit"]) -# parse the arguments args_cli = parser.parse_args() -# launch omniverse app -app_launcher = AppLauncher(args_cli) -simulation_app = app_launcher.app - -"""Rest everything follows.""" - import numpy as np import torch import isaaclab.sim as sim_utils -from isaaclab.assets import Articulation ## # Pre-defined configs ## +from isaaclab.physics import PhysicsCfg + +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg # isort:skip from isaaclab_assets.robots.allegro import ALLEGRO_HAND_CFG # isort:skip from isaaclab_assets.robots.shadow_hand import SHADOW_HAND_CFG # isort:skip +from isaaclab_tasks.core.shadow_hand.shadow_hand_env_cfg import ShadowHandRobotCfg # isort:skip + +if TYPE_CHECKING: + from isaaclab.assets import Articulation def define_origins(num_origins: int, spacing: float) -> list[list[float]]: @@ -78,12 +88,15 @@ def design_scene() -> tuple[dict, list[list[float]]]: # Origin 1 with Allegro Hand sim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0]) # -- Robot - allegro = Articulation(ALLEGRO_HAND_CFG.replace(prim_path="/World/Origin1/Robot")) + allegro_cfg = ALLEGRO_HAND_CFG.replace(prim_path="/World/Origin1/Robot") + allegro = allegro_cfg.class_type(allegro_cfg) # Origin 2 with Shadow Hand sim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1]) # -- Robot - shadow_hand = Articulation(SHADOW_HAND_CFG.replace(prim_path="/World/Origin2/Robot")) + shadow_hand_cfg = ShadowHandRobotCfg().newton_mjwarp if args_cli.physics == "newton_mjwarp" else SHADOW_HAND_CFG + shadow_hand_cfg = shadow_hand_cfg.replace(prim_path="/World/Origin2/Robot") + shadow_hand = shadow_hand_cfg.class_type(shadow_hand_cfg) # return the scene information scene_entities = { @@ -93,7 +106,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: return scene_entities, origins -def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor): +def run_simulator(sim: "sim_utils.SimulationContext", entities: dict[str, "Articulation"], origins: torch.Tensor): """Runs the simulation loop.""" # Define simulation stepping sim_dt = sim.get_physics_dt() @@ -101,8 +114,8 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula count = 0 # Start with hand open grasp_mode = 0 - # Simulate physics - while simulation_app.is_running(): + # Step while a visualizer window is still open (or none exist, e.g. headless); works for kit and newton. + while sim.is_headless_or_exist_active_visualizer(): # reset if count % 1000 == 0: # reset counters @@ -149,24 +162,34 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula def main(): """Main function.""" - # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) - sim = sim_utils.SimulationContext(sim_cfg) - # Set main camera - sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) - # design scene - scene_entities, scene_origins = design_scene() - scene_origins = torch.tensor(scene_origins, device=sim.device) - # Play the simulator - sim.reset() - # Now we are ready! - print("[INFO]: Setup complete...") - # Run the simulator - run_simulator(sim, scene_entities, scene_origins) + with launch_simulation(cfg=PhysicsCfg(), launcher_args=args_cli) as physics_cfg: + # The default newton mjwarp solver configuration needs to be tuned for these hands. + if isinstance(physics_cfg, NewtonCfg) and isinstance(physics_cfg.solver_cfg, MJWarpSolverCfg): + physics_cfg.solver_cfg.njmax = 200 + physics_cfg.solver_cfg.nconmax = 70 + physics_cfg.solver_cfg.impratio = 10.0 + physics_cfg.solver_cfg.cone = "elliptic" + physics_cfg.solver_cfg.update_data_interval = 2 + physics_cfg.solver_cfg.ccd_iterations = 50 + physics_cfg.num_substeps = 2 + physics_cfg.debug_mode = False + + # Initialize the simulation context + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device, physics=physics_cfg) + sim = sim_utils.SimulationContext(sim_cfg) + # Set main camera + sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.05, 0.45]) + # design scene + scene_entities, scene_origins = design_scene() + scene_origins = torch.tensor(scene_origins, device=sim.device) + # Play the simulator + sim.reset() + # Now we are ready! + print("[INFO]: Setup complete...") + # Run the simulator + run_simulator(sim, scene_entities, scene_origins) if __name__ == "__main__": # run the main execution main() - # close sim app - simulation_app.close() diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index f3e15ff899d2..2c8215cbc152 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -8,121 +8,123 @@ .. code-block:: bash - # Usage + # Usage with default PhysX physics and default kit visualizer. ./isaaclab.sh -p scripts/demos/quadcopter.py + # Usage with Newton visualizer and default PhysX physics. + ./isaaclab.sh -p scripts/demos/quadcopter.py --visualizer newton + + # Usage with Newton (MJWarp) physics and default kit visualizer. + ./isaaclab.sh -p scripts/demos/quadcopter.py --physics newton_mjwarp + + # Usage with Newton visualizer and Newton (MJWarp) physics. + ./isaaclab.sh -p scripts/demos/quadcopter.py --visualizer newton --physics newton_mjwarp + """ -"""Launch Isaac Sim Simulator first.""" +"""Parse CLI first so we can decide whether to launch Isaac Sim Kit.""" import argparse -from isaaclab.app import AppLauncher +from isaaclab.app import add_launcher_args, launch_simulation -# add argparse arguments -parser = argparse.ArgumentParser(description="This script demonstrates how to simulate a quadcopter.") -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# demos should open Kit visualizer by default +parser = argparse.ArgumentParser( + description="This script demonstrates how to simulate a quadcopter.", + conflict_handler="resolve", +) +parser.add_argument("--physics", default="physx", choices=["physx", "newton_mjwarp"], help="Physics backend.") +add_launcher_args(parser) parser.set_defaults(visualizer=["kit"]) -# parse the arguments args_cli = parser.parse_args() -# launch omniverse app -app_launcher = AppLauncher(args_cli) -simulation_app = app_launcher.app - -"""Rest everything follows.""" - import torch import isaaclab.sim as sim_utils -from isaaclab.assets import Articulation -from isaaclab.sim import SimulationContext ## # Pre-defined configs ## +from isaaclab.physics import PhysicsCfg + from isaaclab_assets import CRAZYFLIE_CFG # isort:skip def main(): """Main function.""" - # Load kit helper - sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) - sim = SimulationContext(sim_cfg) - # Set main camera - sim.set_camera_view(eye=[0.5, 0.5, 1.0], target=[0.0, 0.0, 0.5]) - - # Spawn things into stage - # Ground-plane - cfg = sim_utils.GroundPlaneCfg() - cfg.func("/World/defaultGroundPlane", cfg) - # Lights - cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75)) - cfg.func("/World/Light", cfg) - - # Robots - robot_cfg = CRAZYFLIE_CFG.replace(prim_path="/World/Crazyflie") - robot_cfg.spawn.func("/World/Crazyflie", robot_cfg.spawn, translation=robot_cfg.init_state.pos) - - # create handles for the robots - robot = Articulation(robot_cfg) - - # Play the simulator - sim.reset() - - # Fetch relevant parameters to make the quadcopter hover in place - prop_body_ids = robot.find_bodies("m.*_prop")[0] - robot_mass = robot.data.body_mass.torch[0].sum() - gravity = torch.tensor(sim.cfg.gravity, device=sim.device).norm() - - # Now we are ready! - print("[INFO]: Setup complete...") - - # Define simulation stepping - sim_dt = sim.get_physics_dt() - sim_time = 0.0 - count = 0 - # Simulate physics - while simulation_app.is_running(): - # reset - if count % 2000 == 0: - # reset counters - sim_time = 0.0 - count = 0 - # reset dof state - joint_pos, joint_vel = robot.data.default_joint_pos.torch, robot.data.default_joint_vel.torch - robot.write_joint_position_to_sim_index(position=joint_pos) - robot.write_joint_velocity_to_sim_index(velocity=joint_vel) - default_root_pose = robot.data.default_root_pose.torch - robot.write_root_pose_to_sim_index(root_pose=default_root_pose) - default_root_vel = robot.data.default_root_vel.torch - robot.write_root_velocity_to_sim_index(root_velocity=default_root_vel) - robot.reset() - # reset command - print(">>>>>>>> Reset!") - # apply action to the robot (make the robot float in place) - forces = torch.zeros(robot.num_instances, 4, 3, device=sim.device) - torques = torch.zeros_like(forces) - forces[..., 2] = robot_mass * gravity / 4.0 - robot.permanent_wrench_composer.set_forces_and_torques( - forces=forces, - torques=torques, - body_ids=prop_body_ids, - ) - robot.write_data_to_sim() - # perform step - sim.step() - # update sim-time - sim_time += sim_dt - count += 1 - # update buffers - robot.update(sim_dt) + with launch_simulation(cfg=PhysicsCfg(), launcher_args=args_cli) as physics_cfg: + # Load kit helper + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, physics=physics_cfg) + sim = sim_utils.SimulationContext(sim_cfg) + # Set main camera + sim.set_camera_view(eye=[0.25, -0.25, 0.7], target=[0.0, 0.0, 0.5]) + + # Spawn things into stage + # Ground-plane + cfg = sim_utils.GroundPlaneCfg() + cfg.func("/World/defaultGroundPlane", cfg) + # Lights + cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75)) + cfg.func("/World/Light", cfg) + + # Robots + robot_cfg = CRAZYFLIE_CFG.replace(prim_path="/World/Crazyflie") + robot_cfg.spawn.func("/World/Crazyflie", robot_cfg.spawn, translation=robot_cfg.init_state.pos) + + # create handles for the robots + robot = robot_cfg.class_type(robot_cfg) + + # Play the simulator + sim.reset() + + # Fetch relevant parameters to make the quadcopter hover in place + prop_body_ids = robot.find_bodies("m.*_prop")[0] + robot_mass = robot.data.body_mass.torch[0].sum() + gravity = torch.tensor(sim.cfg.gravity, device=sim.device).norm() + + # Now we are ready! + print("[INFO]: Setup complete...") + + # Define simulation stepping + sim_dt = sim.get_physics_dt() + sim_time = 0.0 + count = 0 + # Step while a visualizer window is still open (or none exist, e.g. headless); works for kit and newton. + while sim.is_headless_or_exist_active_visualizer(): + # reset + if count % 2000 == 0: + # reset counters + sim_time = 0.0 + count = 0 + # reset dof state + joint_pos, joint_vel = robot.data.default_joint_pos.torch, robot.data.default_joint_vel.torch + robot.write_joint_position_to_sim_index(position=joint_pos) + robot.write_joint_velocity_to_sim_index(velocity=joint_vel) + default_root_pose = robot.data.default_root_pose.torch + robot.write_root_pose_to_sim_index(root_pose=default_root_pose) + default_root_vel = robot.data.default_root_vel.torch + robot.write_root_velocity_to_sim_index(root_velocity=default_root_vel) + robot.reset() + # reset command + print(">>>>>>>> Reset!") + # apply action to the robot (make the robot float in place) + forces = torch.zeros(robot.num_instances, 4, 3, device=sim.device) + torques = torch.zeros_like(forces) + forces[..., 2] = robot_mass * gravity / 4.0 + robot.permanent_wrench_composer.set_forces_and_torques_index( + forces=forces, + torques=torques, + body_ids=prop_body_ids, + ) + robot.write_data_to_sim() + # perform step + sim.step() + # update sim-time + sim_time += sim_dt + count += 1 + # update buffers + robot.update(sim_dt) if __name__ == "__main__": # run the main function main() - # close sim app - simulation_app.close() diff --git a/scripts/demos/quadrupeds.py b/scripts/demos/quadrupeds.py index ec3718ce830f..901c91e0b425 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -8,12 +8,18 @@ .. code-block:: bash - # Usage with the default PhysX backend (launches Isaac Sim Kit). + # Usage with default PhysX physics and default kit visualizer. ./isaaclab.sh -p scripts/demos/quadrupeds.py - # Usage with the kit-less Newton (MJWarp) backend. + # Usage with Newton visualizer and default PhysX physics. + ./isaaclab.sh -p scripts/demos/quadrupeds.py --visualizer newton + + # Usage with Newton (MJWarp) physics and default kit visualizer. ./isaaclab.sh -p scripts/demos/quadrupeds.py --physics newton_mjwarp + # Usage with Newton visualizer and Newton (MJWarp) physics. + ./isaaclab.sh -p scripts/demos/quadrupeds.py --visualizer newton --physics newton_mjwarp + """ """Parse CLI first so we can decide whether to launch Isaac Sim Kit.""" @@ -21,15 +27,15 @@ import argparse from typing import TYPE_CHECKING +from isaaclab.app import add_launcher_args, launch_simulation + parser = argparse.ArgumentParser( description="This script demonstrates different legged robots.", conflict_handler="resolve", ) -from isaaclab.app import add_launcher_args, launch_simulation - parser.add_argument("--physics", default="physx", choices=["physx", "newton_mjwarp"], help="Physics backend.") add_launcher_args(parser) -# parse the arguments +parser.set_defaults(visualizer=["kit"]) args_cli = parser.parse_args() import numpy as np @@ -50,7 +56,7 @@ from isaaclab.assets import Articulation -def define_origins(num_origins: int, spacing: float) -> list[list[float]]: +def define_origins(num_origins: int, spacing: float) -> torch.Tensor: """Defines the origins of the scene.""" # create tensor based on number of environments env_origins = torch.zeros(num_origins, 3) @@ -62,10 +68,10 @@ def define_origins(num_origins: int, spacing: float) -> list[list[float]]: env_origins[:, 1] = spacing * yy.flatten()[:num_origins] - spacing * (num_cols - 1) / 2 env_origins[:, 2] = 0.0 # return the origins - return env_origins.tolist() + return env_origins -def design_scene() -> tuple[dict, list[list[float]]]: +def design_scene() -> tuple[dict, torch.Tensor]: """Designs the scene.""" # Ground-plane cfg = sim_utils.GroundPlaneCfg() @@ -83,6 +89,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: # -- Robot anymal_b_cfg = ANYMAL_B_CFG.replace(prim_path="/World/Origin1/Robot") anymal_b = anymal_b_cfg.class_type(anymal_b_cfg) + # Origin 2 with Anymal C sim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1]) # -- Robot @@ -132,18 +139,16 @@ def design_scene() -> tuple[dict, list[list[float]]]: return scene_entities, origins -def run_simulator(sim, entities: dict[str, "Articulation"], origins: torch.Tensor): +def run_simulator(sim: "sim_utils.SimulationContext", entities: dict[str, "Articulation"], origins: torch.Tensor): """Runs the simulation loop.""" # Define simulation stepping sim_dt = sim.get_physics_dt() - sim_time = 0.0 count = 0 # Step while a visualizer window is still open (or none exist, e.g. headless); works for kit and newton. - while not sim.visualizers or any(v.is_running() and not v.is_closed for v in sim.visualizers): - # reset + while sim.is_headless_or_exist_active_visualizer(): + # Reset robots every 200 steps. if count % 200 == 0: # reset counters - sim_time = 0.0 count = 0 # reset robots for index, robot in enumerate(entities.values()): @@ -154,16 +159,14 @@ def run_simulator(sim, entities: dict[str, "Articulation"], origins: torch.Tenso root_vel = robot.data.default_root_vel.torch.clone() robot.write_root_velocity_to_sim_index(root_velocity=root_vel) # joint state - joint_pos, joint_vel = ( - robot.data.default_joint_pos.torch.clone(), - robot.data.default_joint_vel.torch.clone(), - ) + joint_pos = robot.data.default_joint_pos.torch.clone() robot.write_joint_position_to_sim_index(position=joint_pos) + joint_vel = robot.data.default_joint_vel.torch.clone() robot.write_joint_velocity_to_sim_index(velocity=joint_vel) # reset the internal state robot.reset() - print("[INFO]: Resetting robots state...") - # apply default actions to the quadrupedal robots + print("[INFO]: Reset robots' state...") + # Apply default actions to the quadrupedal robots. for robot in entities.values(): # generate random joint positions joint_pos_target = robot.data.default_joint_pos.torch + torch.randn_like(robot.data.joint_pos.torch) * 0.1 @@ -173,8 +176,7 @@ def run_simulator(sim, entities: dict[str, "Articulation"], origins: torch.Tenso robot.write_data_to_sim() # perform step sim.step() - # update sim-time - sim_time += sim_dt + # update counter count += 1 # update buffers for robot in entities.values(): @@ -185,16 +187,11 @@ def main(): """Main function.""" with launch_simulation(cfg=PhysicsCfg(), launcher_args=args_cli) as physics_cfg: dt = 1 / 200 - sim = sim_utils.SimulationContext( - sim_utils.SimulationCfg( - dt=dt, - device=args_cli.device, - physics=physics_cfg, - ) - ) + sim_cfg: sim_utils.SimulationCfg = sim_utils.SimulationCfg(dt=dt, device=args_cli.device, physics=physics_cfg) + sim = sim_utils.SimulationContext(sim_cfg) sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) scene_entities, scene_origins = design_scene() - scene_origins = torch.tensor(scene_origins, device=sim.device) + scene_origins = scene_origins.to(sim.device) sim.reset() print("[INFO]: Setup complete...") run_simulator(sim, scene_entities, scene_origins) diff --git a/source/isaaclab/changelog.d/yizew-support-multi-backends.rst b/source/isaaclab/changelog.d/yizew-support-multi-backends.rst new file mode 100644 index 000000000000..3b07fde871f0 --- /dev/null +++ b/source/isaaclab/changelog.d/yizew-support-multi-backends.rst @@ -0,0 +1,14 @@ +Added +^^^^^ + +* Added :attr:`~isaaclab.scene.InteractiveSceneCfg.class_type` so scene configs + can instantiate custom scene classes. +* Added :meth:`~isaaclab.sim.SimulationContext.is_headless_or_exist_active_visualizer` + to let kitless and external-visualizer demos share a visualizer-aware stepping + condition. + +Changed +^^^^^^^ + +* Updated demo scripts to support selectable PhysX or Newton MJWarp physics + backends and Kit or Newton visualizers. diff --git a/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py b/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py index 034307017219..be5fa82fd7d0 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py @@ -3,10 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause +from __future__ import annotations + from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.utils.configclass import configclass +if TYPE_CHECKING: + from .interactive_scene import InteractiveScene + @configclass class InteractiveSceneCfg: @@ -67,6 +73,12 @@ class MySceneCfg(InteractiveSceneCfg): """ + class_type: type[InteractiveScene] | str = "{DIR}.interactive_scene:InteractiveScene" + """The class to use for the interactive scene. + + Defaults to :class:`isaaclab.scene.InteractiveScene`. + """ + num_envs: int = MISSING """Number of environment instances handled by the scene.""" diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index c068469ec599..8b1400b6d8ed 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -391,6 +391,10 @@ def has_active_visualizers(self) -> bool: self.get_setting("/isaaclab/video/auto_start_kit") ) + def is_headless_or_exist_active_visualizer(self) -> bool: + """Return whether the simulation should keep stepping without visualizers or with an active visualizer.""" + return not self._visualizers or any(viz.is_running() and not viz.is_closed for viz in self._visualizers) + def can_render_rgb_array(self) -> bool: """Return whether rgb-array rendering is currently available.""" return self.has_gui or self.has_offscreen_render or self.has_active_visualizers() diff --git a/source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst b/source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst new file mode 100644 index 000000000000..7a1cd353d7ec --- /dev/null +++ b/source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst @@ -0,0 +1,6 @@ +Added +^^^^^ + +* Added :meth:`~isaaclab_visualizers.newton.NewtonVisualizer.set_camera_view` so + the Newton visualizer follows :meth:`~isaaclab.sim.SimulationContext.set_camera_view` + camera updates. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index 3dbecdec794f..7a8ecfc2bb2b 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -742,6 +742,20 @@ def _apply_camera_focal_length(self) -> None: return self._viewer.camera.fov = self._focal_length_to_vertical_fov_degrees() + def set_camera_view( + self, eye: tuple[float, float, float] | list[float], target: tuple[float, float, float] | list[float] + ) -> None: + """Set active viewer camera eye/target. + + Args: + eye: Camera eye position. + target: Camera look-at target. + """ + if not self._is_initialized: + logger.debug("[NewtonVisualizer] set_camera_view() ignored because visualizer is not initialized.") + return + self._apply_camera_pose((tuple(eye), tuple(target))) + def supports_markers(self) -> bool: """Newton OpenGL viewer supports Isaac Lab markers through viewer-side meshes and lines.""" return bool(self.cfg.enable_markers) From c7cbe661d077327543179d4f7d3af10b95bbcfe8 Mon Sep 17 00:00:00 2001 From: ooctipus Date: Sun, 7 Jun 2026 17:32:29 -0700 Subject: [PATCH 13/40] Decouple backend-specific cloning from InteractiveScene (#5770) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Summary This PR removes backend-specific cloning logic from `InteractiveScene` and replaces the previous implicit `replicate_session_defaults` / `replicate_session` machinery with three orthogonal, explicit primitives that compose identically whether you drive cloning through `InteractiveScene` or by hand in a `DirectRLEnv` or standalone script. The result is that `InteractiveScene` no longer knows anything about USD vs. PhysX vs. Newton — it just enters a `ReplicateSession` and lets each asset's constructor register the backend(s) it needs. This is foundational for two follow-on capabilities the project has wanted for a while: **flexible backend cloning** and **skip-cloning workflows**. ## What changed ### New core primitives in `isaaclab.cloner` - **`REPLICATION_QUEUE`** — module-level list that asset constructors append `(cfg, BackendCtxCls)` pairs to via tiny per-backend helpers (`queue_usd_replication`, `queue_physx_replication`, `queue_newton_replication`). Backends are no longer special-cased inside `InteractiveScene`; each one self-registers. - **`ClonePlan`** — self-contained dataclass describing the world layout (`sources`, `destinations`, `clone_mask`, `env_ids`, `positions`, `cfg_rows`). Stage-agnostic by design; the USD stage is now passed explicitly to consumers so the same plan can be replayed, inspected, or serialized. - **`replicate(plan, *, stage)`** — free function that drains `REPLICATION_QUEUE` against a plan, groups queued cfgs by backend context class, runs each context in ascending `replicate_priority` order (physics before USD), publishes the plan to `SimulationContext`, and clears the queue. The queue is snapshotted and cleared up front so a backend failure cannot leak stale entries into the next call. - **`ReplicateSession`** is now a thin context manager that calls `make_clone_plan` in `__enter__` and `replicate` in `__exit__`. The state-bag version with `plan` / `stage` / `cfg_rows` / `replicate_on_exit` fields is gone. - **`ClonePlan.from_env_0`** — classmethod that builds the single-source homogeneous plan most direct envs need by auto-populating `cfg_rows` from `REPLICATION_QUEUE` filtered by env-root prefix. - **`CloneCfg.clone_regex`** (default `"/World/envs/env_.*"`) — single source of truth for the env-namespace convention. `InteractiveScene` reads it directly when expanding `{ENV_REGEX_NS}` cfg macros. ### Two equivalent invocation paths ```python # InteractiveScene path (what the scene runs under the hood) with cloner.ReplicateSession(cfgs, num_clones=N, env_spacing=2.0, device=device, stage=stage): for cfg in cfgs: cfg.class_type(cfg) # Direct env / script path plan = cloner.ClonePlan.from_env_0(src, dest, num_envs, device, positions) cloner.replicate(plan, stage=scene.stage) ``` Both end in the same `cloner.replicate(plan, stage=...)` call. The only difference is how the plan was built and how asset construction was interleaved. ### What got removed from `InteractiveScene` - `clone_environments(...)` deprecated shim. The scene now replicates inside `__init__` via `ReplicateSession`. - `env_ns` / `env_regex_ns` properties (used only internally). - `_build_clone_plan_from_cfg` and `_default_env_origins` internals. Cfg-driven plan construction now lives in `make_clone_plan`; per-env positions are read from the published `ClonePlan`. - `InteractiveScene.env_origins` now reads from the plan published to `SimulationContext`, making the plan the single source of truth for env placement. ### Why this matters (the actual point of the PR) This refactor is foundational for two capabilities the current scene coupling blocks: - **Flexible backend cloning.** Backends now plug in by shipping a `ReplicateContext` class + a one-line queue helper. Swapping PhysX ↔ Newton no longer requires `InteractiveScene` to change; cfgs and user code stay untouched, and a third-party backend can register itself without modifying core. - **Skip-cloning workflows.** Because plan construction, asset registration, and drain are three independent primitives, callers that want to author env-0 prims by hand and skip the cloner — or drive replication out-of-band from a visualizer, replay tool, or test fixture — can do so without fighting `InteractiveScene`. ## Migration notes - `with cloner.ReplicateSession():` (no-arg) → `cloner.replicate(cloner.ClonePlan.from_env_0(...), stage=...)`. - `InteractiveScene.clone_environments(...)` → removed; the scene replicates inside `__init__`. - `make_clone_plan(sources, destinations, ...)` → `make_clone_plan(cfgs, num_clones, env_spacing, device, ...)`. - Pass `stage=...` explicitly to `replicate()` and `ReplicateSession()`. - Read `CloneCfg.clone_regex` if you previously used `InteractiveScene.env_ns` / `env_regex_ns`. About 17 direct envs were migrated to the new pattern in this PR. ## Test plan - [ ] `./isaaclab.sh -p -m pytest source/isaaclab/test/sim/test_cloner.py` - [ ] `./isaaclab.sh -p -m pytest source/isaaclab/test/scene/test_interactive_scene.py` - [ ] `./isaaclab.sh -p -m pytest source/isaaclab_physx/test/sim/test_cloner.py` - [ ] Migrated direct envs (`cartpole`, `anymal_c`, `franka_cabinet`, `factory`, `humanoid_amp`, `inhand_manipulation`, `locomotion`, `quadcopter`, `shadow_hand_*`, `automate/*`, `cart_double_pendulum`, `cartpole_warp`, `inhand_manipulation_warp`, `locomotion_warp`) spawn and step on PhysX - [ ] Same envs spawn and step on Newton - [ ] `./isaaclab.sh -f` passes - [ ] Docs build (`cd docs && make html`) --- docs/source/how-to/cloning.rst | 572 +++++++++--------- .../migration/migrating_from_isaacgymenvs.rst | 15 +- .../migrating_from_omniisaacgymenvs.rst | 6 +- .../setup/walkthrough/api_env_design.rst | 11 +- .../walkthrough/technical_env_design.rst | 9 +- .../setup/walkthrough/training_jetbot_gt.rst | 9 +- scripts/demos/pick_and_place.py | 7 +- scripts/tutorials/06_deploy/anymal_c_env.py | 6 +- .../replication-session-redesign.minor.rst | 49 ++ source/isaaclab/isaaclab/cloner/__init__.pyi | 20 +- .../isaaclab/cloner/_fabric_notices.py | 58 ++ source/isaaclab/isaaclab/cloner/clone_plan.py | 72 ++- source/isaaclab/isaaclab/cloner/cloner_cfg.py | 29 +- .../isaaclab/isaaclab/cloner/cloner_utils.py | 348 +++++------ .../isaaclab/cloner/replicate_session.py | 135 +++++ source/isaaclab/isaaclab/cloner/usd.py | 185 ++++++ .../isaaclab/scene/interactive_scene.py | 273 +++------ .../isaaclab/scene/interactive_scene_cfg.py | 13 +- .../isaaclab/sensors/camera/camera.py | 2 + .../sensors/ray_caster/base_ray_caster.py | 2 + .../isaaclab/isaaclab/sensors/sensor_base.py | 8 +- .../isaaclab/sim/simulation_context.py | 8 +- .../test/scene/test_interactive_scene.py | 313 ++-------- .../generate_synthetic_gaussian_asset.py | 9 + .../test_multi_mesh_ray_caster_camera.py | 3 + .../sensors/test_ray_caster_integration.py | 3 + source/isaaclab/test/sim/test_cloner.py | 430 +++++++++++-- ...ix-newton-deformable-clone-replication.rst | 4 + .../coupled_featherstone_vbd_manager.py | 37 +- .../deformable/coupled_mjwarp_vbd_manager.py | 37 +- .../deformable/deformable_object.py | 60 ++ .../deformable/vbd_manager.py | 37 +- .../test_deformable_builder_hooks.py | 103 +++- .../replication-session-redesign.skip | 5 + .../assets/articulation/articulation.py | 2 + .../assets/rigid_object/rigid_object.py | 2 + .../rigid_object_collection.py | 5 +- .../isaaclab_newton/cloner/__init__.pyi | 9 +- .../{newton_replicate.py => replicate.py} | 249 +++++--- .../test/cloner/test_rename_builder_labels.py | 2 +- .../replication-session-redesign.skip | 0 .../assets/articulation/articulation.py | 4 + .../assets/rigid_object/rigid_object.py | 4 + .../rigid_object_collection.py | 6 +- .../isaaclab_ovphysx/cloner/__init__.py | 4 +- .../cloner/ovphysx_replicate.py | 105 ---- .../isaaclab_ovphysx/cloner/replicate.py | 185 ++++++ .../physics/ovphysx_manager.py | 11 +- .../replication-session-redesign.skip | 5 + .../assets/articulation/articulation.py | 4 + .../deformable_object/deformable_object.py | 4 + .../assets/rigid_object/rigid_object.py | 4 + .../rigid_object_collection.py | 6 +- .../assets/surface_gripper/surface_gripper.py | 6 + .../isaaclab_physx/cloner/__init__.pyi | 4 +- .../isaaclab_physx/cloner/physx_replicate.py | 113 ---- .../isaaclab_physx/cloner/replicate.py | 196 ++++++ source/isaaclab_physx/test/sim/test_cloner.py | 79 ++- .../replication-session-redesign.skip | 4 + .../contrib/anymal_c_direct/anymal_c_env.py | 7 +- .../contrib/automate/assembly_env.py | 6 +- .../contrib/automate/disassembly_env.py | 6 +- .../contrib/factory/factory_env.py | 6 +- .../contrib/humanoid_amp/humanoid_amp_env.py | 7 +- .../cart_double_pendulum_env.py | 7 +- .../cartpole/cartpole_direct_camera_env.py | 7 +- .../core/cartpole/cartpole_direct_env.py | 9 +- .../core/franka_cabinet/franka_cabinet_env.py | 7 +- .../inhand_manipulation_env.py | 7 +- .../core/locomotion/locomotion_direct_env.py | 7 +- .../shadow_hand/shadow_hand_vision_env.py | 7 +- .../shadow_hand_over/shadow_hand_over_env.py | 7 +- .../direct/cartpole/cartpole_warp_env.py | 7 +- .../inhand_manipulation_warp_env.py | 7 +- .../direct/locomotion/locomotion_env_warp.py | 7 +- .../templates/tasks/direct_multi-agent/env | 8 +- .../templates/tasks/direct_single-agent/env | 8 +- 77 files changed, 2439 insertions(+), 1579 deletions(-) create mode 100644 source/isaaclab/changelog.d/replication-session-redesign.minor.rst create mode 100644 source/isaaclab/isaaclab/cloner/replicate_session.py create mode 100644 source/isaaclab/isaaclab/cloner/usd.py create mode 100644 source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst create mode 100644 source/isaaclab_newton/changelog.d/replication-session-redesign.skip rename source/isaaclab_newton/isaaclab_newton/cloner/{newton_replicate.py => replicate.py} (63%) create mode 100644 source/isaaclab_ovphysx/changelog.d/replication-session-redesign.skip delete mode 100644 source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py create mode 100644 source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/replicate.py create mode 100644 source/isaaclab_physx/changelog.d/replication-session-redesign.skip delete mode 100644 source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py create mode 100644 source/isaaclab_physx/isaaclab_physx/cloner/replicate.py create mode 100644 source/isaaclab_tasks/changelog.d/replication-session-redesign.skip diff --git a/docs/source/how-to/cloning.rst b/docs/source/how-to/cloning.rst index 16d5bcece155..8f3710acc11e 100644 --- a/docs/source/how-to/cloning.rst +++ b/docs/source/how-to/cloning.rst @@ -5,350 +5,361 @@ Cloning Environments .. currentmodule:: isaaclab -Isaac Lab creates many parallel environments by spawning representative source prims and -then cloning them to the remaining environment paths. This guide starts with direct cloning -so the primitive contract is clear, then shows how :class:`~isaaclab.cloner.ClonePlan` and -:class:`~isaaclab.scene.InteractiveScene` build on top of that contract. +Parallel simulation at scale needs many environments stepping side by side — +hundreds, sometimes tens of thousands per GPU — and authoring each of those envs +by hand would be hopelessly slow. Cloning is Isaac Lab's answer: you author a +small representative scene under ``/World/envs/env_n`` and the cloner expands it +across the rest of the env population for you, optionally with per-env variation. + +The expansion itself is performed by each physics backend's native replicator — +USD, PhysX, or Newton — wrapped by Isaac Lab's core :mod:`isaaclab.cloner` module +behind a single uniform surface so the same user code works regardless of which +backend is active. .. contents:: On this page :local: :depth: 2 -Direct Cloning --------------- +The Backend Layer +----------------- + +At the bottom of the stack, each backend exposes a single function that takes a +flat description of the world layout and materializes it on its runtime. The +signatures are deliberately parallel so the layers above can target every backend +through one interface: + +.. code-block:: text -Use direct cloning for custom scene pipelines, tooling, or tests that need explicit -control over the replication contract. + backend_replicate(stage, sources, destinations, env_ids, mask, positions=None, quaternions=None, ...) -The cloner operates on three pieces of data: +The arguments are parallel arrays describing the layout: -1. **Source prims** that already exist on the stage. -2. **Destination templates** containing ``{}``, which is formatted with each environment id. -3. **A boolean mask** with shape ``[len(sources), num_envs]`` that selects which source - populates each environment. +* ``sources`` — source prim paths already authored on the stage. +* ``destinations`` — destination templates containing ``"{}"``, formatted with each env id. +* ``env_ids`` — long tensor of target env indices. +* ``mask`` — bool tensor of shape ``[len(sources), num_envs]``; ``mask[i, j]`` is + ``True`` when env ``j`` should be populated from source ``i``. +* ``positions`` / ``quaternions`` — optional per-env world transforms. -The direct flow is: -1. Create the environment namespace prims. -2. Spawn representative source prims. -3. Call the physics replicate function for your backend. -4. Call :func:`~isaaclab.cloner.usd_replicate` with the same source-to-environment mapping. +Standalone Examples +~~~~~~~~~~~~~~~~~~~ + +Direct calls into the backend functions, for tooling or tests that need full +control. Production code reaches for one of the ways in +`Cloning in a Backend-Agnostic Way`_ instead. + +**USD** — clone a visual cube across envs: .. code-block:: python import torch - import isaaclab.sim as sim_utils from isaaclab.cloner import usd_replicate - from isaaclab_physx.cloner import physx_replicate num_envs = 128 stage = sim_utils.get_current_stage() - env_ids = torch.arange(num_envs, device="cuda:0") - - sim_utils.create_prim("/World/envs", "Xform") - for env_id in range(num_envs): - sim_utils.create_prim(f"/World/envs/env_{env_id}", "Xform") - - source = "/World/envs/env_0/Cube" - destination = "/World/envs/env_{}/Object" + cube_cfg = sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)) + cube_cfg.func("/World/envs/env_0/Cube", cube_cfg) + + usd_replicate( + stage, + sources=["/World/envs/env_0/Cube"], + destinations=["/World/envs/env_{}/Cube"], + env_ids=torch.arange(num_envs, device="cuda:0"), + mask=torch.ones((1, num_envs), dtype=torch.bool, device="cuda:0"), + ) - cube_cfg = sim_utils.CuboidCfg(size=(0.5, 0.5, 0.5)) - cube_cfg.func(source, cube_cfg) +**PhysX** — call PhysX and USD on the same sources and destinations (either order): - mask = torch.ones((1, num_envs), dtype=torch.bool, device="cuda:0") +.. code-block:: python - physx_replicate(stage, [source], [destination], env_ids, mask, device="cuda:0") - usd_replicate(stage, [source], [destination], env_ids, mask) + from isaaclab_physx.cloner import physx_replicate -This creates one source cube at ``/World/envs/env_0/Cube`` and clones it to -``/World/envs/env_1/Object`` through ``/World/envs/env_127/Object``. When a source path is -the same as the destination for an environment, ``usd_replicate`` skips the self-copy. + physx_replicate(stage, sources, destinations, env_ids, mask) + usd_replicate(stage, sources, destinations, env_ids, mask) -Direct heterogeneous cloning uses the same API with more source rows. Each row in ``mask`` -selects the environments that receive the matching source. For example, this explicit mask -clones a cone into environments 0 and 2, and a sphere into environments 1 and 3: +**Newton**: .. code-block:: python - env_ids = torch.arange(4, device="cuda:0") - sources = ["/World/envs/env_0/Cone", "/World/envs/env_1/Sphere"] - destinations = ["/World/envs/env_{}/Object", "/World/envs/env_{}/Object"] + from isaaclab_newton.cloner import newton_physics_replicate - cone_cfg = sim_utils.ConeCfg(radius=0.25, height=0.5) - sphere_cfg = sim_utils.SphereCfg(radius=0.25) - cone_cfg.func(sources[0], cone_cfg) - sphere_cfg.func(sources[1], sphere_cfg) + newton_physics_replicate(stage, sources, destinations, env_ids, mapping=mask) - mask = torch.tensor([[True, False, True, False], [False, True, False, True]], dtype=torch.bool) - physx_replicate(stage, sources, destinations, env_ids, mask, device="cuda:0") - usd_replicate(stage, sources, destinations, env_ids, mask) +Cloning in a Backend-Agnostic Way +--------------------------------- -The mask above reads as: +Authoring every prim in every env by hand would be prohibitively slow and would +also tie scene code to whichever physics engine happens to be active. Isaac Lab +sidesteps both problems with a single central abstraction: +:class:`~isaaclab.cloner.ClonePlan` — a compact description of how a small set of +prim-level prototypes maps onto the full population of envs, with each prototype +free to land in some envs and not others. A plan is built once, fed to each backend, and +lets every engine take its own fastest replication path: USD instancing for +visuals, PhysX's native replicator for rigid bodies and articulations, Newton's +world system for its parallel pipeline. The same plan drives all of them, so user +code never branches on the backend. + +ClonePlan +~~~~~~~~~ + +A plan holds the parallel arrays a backend replicate consumes — sources, +destinations, mask, env ids — in one place. Conceptually it is a small table +where each row describes one distinct prototype-to-destination mapping; the +fields listed below are that table's columns. Every entry point in +:mod:`isaaclab.cloner` either produces a plan, consumes a plan, or both, so a +quick look at the fields is the fastest way to build intuition for the rest of +this page: .. list-table:: :header-rows: 1 - :widths: 15 40 20 25 - - * - Source row - - Source path - - Env ids - - Destination path - * - ``0`` - - ``/World/envs/env_0/Cone`` - - ``0, 2`` - - ``/World/envs/env_{}/Object`` - * - ``1`` - - ``/World/envs/env_1/Sphere`` - - ``1, 3`` - - ``/World/envs/env_{}/Object`` - -``usd_replicate`` copies parent paths before children and supports optional ``positions`` -and ``quaternions`` buffers. If ``positions`` is provided, it authors -``xformOp:translate`` on each destination using the environment id. The helper -:func:`~isaaclab.cloner.grid_transforms` creates the same grid layout used by -:class:`~isaaclab.scene.InteractiveScene`. - -.. code-block:: python + :widths: 22 78 - from isaaclab.cloner import grid_transforms - - positions, orientations = grid_transforms( - N=num_envs, - spacing=2.0, - up_axis="z", - device="cuda:0", - ) - usd_replicate(stage, [source], [destination], env_ids, mask, positions=positions) - - -Clone Plans ------------ - -For one source row, passing ``sources``, ``destinations``, and ``mask`` by hand is simple. -For heterogeneous scenes, the mapping is easier to build with -:func:`~isaaclab.cloner.make_clone_plan`, which returns the raw flat components. Composing -those components into a :class:`~isaaclab.cloner.ClonePlan` together with the per-environment -pose buffer is the caller's responsibility — keeping pose authority on the side that owns the -buffer (typically the scene) avoids duplicating tensors. - -:class:`~isaaclab.cloner.ClonePlan` stores the same flat contract used by direct cloning: + * - Field + - Meaning + * - ``sources`` + - Source prim paths, one per replication row. + * - ``destinations`` + - Destination templates with ``"{}"`` for the env id, one per row. + * - ``clone_mask`` + - Bool tensor ``[len(sources), num_envs]``; ``True`` when env ``j`` comes from row ``i``. + * - ``env_ids`` + - Long tensor of target env ids. + * - ``positions`` + - Optional per-env world positions [m], shape ``[num_envs, 3]``. + +The plan is stage-agnostic by design — the same instance can be replayed against a +different stage, inspected by tooling, or serialized. + +When every env is a copy of env_0: .. code-block:: text - sources = [source_0, source_1, ...] - destinations = [destination_0, destination_1, ...] - clone_mask = bool tensor, shape [len(sources), num_envs] + sources = ("/World/envs/env_0",) + destinations = ("/World/envs/env_{}",) + clone_mask = [[True, True, ..., True]] -``clone_mask[i, j]`` is ``True`` when environment ``j`` should receive source row ``i``. -The same plan can be passed to USD replication, physics replication, and scene-data -providers. +When envs differ — say a cartpole in every env plus a 2-variant obstacle (box into +envs 0/1, sphere into envs 2/3): -Homogeneous Plans -~~~~~~~~~~~~~~~~~ +.. code-block:: text -In a homogeneous scene, every environment receives the same asset layout. The default plan -is: + sources = ("/World/envs/env_0/Cartpole", + "/World/envs/env_0/Obstacle_0", # box prototype + "/World/envs/env_0/Obstacle_1") # sphere prototype + destinations = ("/World/envs/env_{}/Cartpole", + "/World/envs/env_{}/Obstacle", + "/World/envs/env_{}/Obstacle") + clone_mask = [[1, 1, 1, 1], + [1, 1, 0, 0], + [0, 0, 1, 1]] + +A plan is the *what*. Putting one together and handing it to the backends is +the *how*, and Isaac Lab exposes three idiomatic ways to do that. All three end +in the same ``cloner.replicate(plan, stage=...)`` call, so the choice between +them is purely about ergonomics: + +* The first wraps both phases in a context manager and is what + :class:`~isaaclab.scene.InteractiveScene` runs under the hood. Reach for it + when you want the lifecycle hidden and you are authoring assets through a + scene config. +* The second spells the same flow out as plain function calls, leaving a moment + between the build and the drain where you can inspect or mutate the plan. + Reach for it when you are assembling a scene outside + :class:`~isaaclab.scene.InteractiveScene` or want fine control over timing. +* The third is a one-shot shortcut for the case where every env is just a copy + of env_0. Reach for it in :class:`~isaaclab.envs.DirectRLEnv` and standalone + scripts that hand-build the env-0 prototype prim by prim. + +``ReplicateSession`` +~~~~~~~~~~~~~~~~~~~~ + +:class:`~isaaclab.cloner.ReplicateSession` is a context manager that brackets the +whole cloning lifecycle. Entering the block builds the plan, the body is where +you construct your assets (each one registers itself as part of its constructor), +and exiting the block drains every registration against the plan: -.. code-block:: text +.. code-block:: python - sources = ["/World/envs/env_0"] - destinations = ["/World/envs/env_{}"] - clone_mask = all True, shape [1, num_envs] + with cloner.ReplicateSession(cfgs, num_clones=N, env_spacing=2.0, + device=device, stage=stage): + for cfg in cfgs: + cfg.class_type(cfg) -This means the scene spawns everything for ``env_0`` and replicates that environment to -``env_1`` through ``env_N``. +This is what :class:`~isaaclab.scene.InteractiveScene` runs when you declare assets +in an :class:`~isaaclab.scene.InteractiveSceneCfg`: -Heterogeneous Plans -~~~~~~~~~~~~~~~~~~~ +.. code-block:: python -Heterogeneous cloning is used when different environments receive different prototypes. -For example, an object with three variants may have representative source prims at: + @configclass + class MySceneCfg(InteractiveSceneCfg): + robot = CARTPOLE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + light = AssetBaseCfg( + prim_path="/World/Light", + spawn=sim_utils.DistantLightCfg(intensity=3000.0), + ) -.. code-block:: text + scene = InteractiveScene(MySceneCfg(num_envs=128, env_spacing=2.0)) - /World/envs/env_0/Object - /World/envs/env_1/Object - /World/envs/env_2/Object +When envs need to differ across the population, use +:class:`~isaaclab.sim.spawners.wrappers.MultiAssetSpawnerCfg` or +:class:`~isaaclab.sim.spawners.wrappers.MultiUsdFileCfg`; see +:doc:`multi_asset_spawning`. -These paths have the same leaf name because each variant will be cloned to -``/World/envs/env_{}/Object``, but their authored contents are different. For example, -``env_0/Object`` could be a cone, ``env_1/Object`` a cuboid, and ``env_2/Object`` a sphere. +``make_clone_plan`` + ``replicate`` +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -The plan maps those source rows to all environments: +The same two phases as the session, written as separate function calls. The plan +is built first, asset construction happens in between, and the drain runs +explicitly at the end. The gap between the build and the drain is the point — +that is where you can read the plan back, mutate it, log it, or otherwise +intervene before replication actually happens: .. code-block:: python - from isaaclab.cloner import make_clone_plan, sequential - - sources, destinations, clone_mask = make_clone_plan( - sources=[ - [ - "/World/envs/env_0/Object", - "/World/envs/env_1/Object", - "/World/envs/env_2/Object", - ] - ], - destinations=["/World/envs/env_{}/Object"], - num_clones=8, - clone_strategy=sequential, - device="cuda:0", - ) + plan = cloner.make_clone_plan(cfgs, num_clones=N, env_spacing=2.0, device=device) + for cfg in cfgs: + cfg.class_type(cfg) + cloner.replicate(plan, stage=stage) - # source row used by env: 0, 1, 2, 0, 1, 2, 0, 1 +``ClonePlan.from_env_0`` + ``replicate`` +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -Direct code can use the components exactly like the hand-written direct example: +Shortcut for the case where every env is just a copy of env_0. +:meth:`~isaaclab.cloner.ClonePlan.from_env_0` builds the single-source plan in +one line by pointing at the prototype, and :func:`~isaaclab.cloner.replicate` +finishes the setup. This is the pattern most :class:`~isaaclab.envs.DirectRLEnv` +subclasses use — they author the env-0 prototype prim by prim in +``_setup_scene`` and end the method with these four lines: .. code-block:: python - physx_replicate(stage, sources, destinations, env_ids, clone_mask, device="cuda:0") - usd_replicate(stage, sources, destinations, env_ids, clone_mask) - -When variants span multiple groups, such as robot variants and object variants, -``make_clone_plan`` enumerates the Cartesian product of the groups and assigns one -combination per environment. Unused prototype rows may still appear in the plan with an -all-false mask row. + def _setup_scene(self): + self.cartpole = Articulation(self.cfg.robot_cfg) + spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) + # ... any other assets ... -.. _cloning-strategies: + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) -Clone Strategies -~~~~~~~~~~~~~~~~ +Every env receives the same prototype. When envs need to differ, use one of the +other two. -A clone strategy chooses prototype combinations for the environments: -* :func:`~isaaclab.cloner.random` samples combinations randomly and is the default. -* :func:`~isaaclab.cloner.sequential` assigns combinations in round-robin order, which is - useful for reproducible tests and balanced coverage. +Under the Hood +-------------- -Custom strategies are callables with this signature: +To see how the backend-agnostic surface works, follow one asset through the +system. Suppose you write ``Articulation(cfg)`` for a PhysX articulation +somewhere inside a :class:`~isaaclab.cloner.ReplicateSession`. The constructor +does not actually clone anything yet — at that moment the plan describing how +the full env population should be laid out may not even exist. Instead the +constructor *registers* the asset with the cloner, the cloner files the +registration into a queue, and later — when the session exits and the cloner +runs replication — that registration is handed to the backend code that knows +how to replicate a PhysX articulation, with the plan telling it where each +clone goes. + +The story has to look like this because the engines underneath disagree about +*when* and *how* replication actually happens: + +* **PhysX** defers the real work to physics runtime. At construction time the + only thing user code can do is register intent; PhysX replays those + registrations entity by entity when the simulation comes up. +* **USD** is declarative and immediate — calling :func:`~isaaclab.cloner.usd_replicate` + materializes the clones in place, right then and there. +* **Newton** is also declarative and immediate, but it insists on replicating + the whole world in one shot rather than asset by asset, so the framework + cannot just hand it one cfg at a time — everything Newton-related has to be + assembled first. + +Isaac Lab reconciles these into one surface with two small pieces of plumbing. +Every backend supplies its own :class:`~isaaclab.cloner.UsdReplicateContext` / +``PhysxReplicateContext`` / ``NewtonReplicateContext``, a class that hides the +timing and granularity differences above behind a single uniform interface. A +shared :data:`~isaaclab.cloner.REPLICATION_QUEUE` then remembers which asset +belongs to which backend's context until it is time to run. The three +subsections below explain the queue, the contexts, and the function that joins +them against a plan. + +The registration queue +~~~~~~~~~~~~~~~~~~~~~~ + +Asset constructors do not replicate inline. They register their intent with +:data:`~isaaclab.cloner.REPLICATION_QUEUE` and the framework defers the actual +work to the drain. The queue ends up holding one entry per ``(asset, backend)`` +pair: -.. code-block:: python +.. code-block:: text - def my_strategy(combinations: torch.Tensor, num_clones: int, device: str) -> torch.Tensor: + REPLICATION_QUEUE + (cartpole_cfg, PhysxReplicateContext) + (cartpole_cfg, UsdReplicateContext) + (cube_cfg, UsdReplicateContext) + (light_cfg, UsdReplicateContext) ... -``combinations`` has shape ``[num_combinations, num_groups]`` and the return value must have -shape ``[num_clones, num_groups]``. - - -Common Workflow: ``InteractiveScene`` -------------------------------------- +Deferring the work like this buys three things at once: -:class:`~isaaclab.scene.InteractiveScene` automates the direct cloning flow for task scenes. -It inspects scene configuration, builds a :class:`~isaaclab.cloner.ClonePlan`, rewrites -spawner paths to the representative sources, spawns those sources, runs physics and USD -replication, and filters inter-environment collisions for PhysX when configured. +* Replication can wait until the plan is fully built, so the final layout is + known before any prims are spawned. +* Every asset's request is batched into a single backend call instead of one + call per asset. +* Asset code stays free of any branching on which backend is active — it just + registers and lets the framework take it from there. -Put per-environment assets under ``{ENV_REGEX_NS}`` and global assets under normal USD -paths: - -.. code-block:: python +Backend contexts +~~~~~~~~~~~~~~~~ - import isaaclab.sim as sim_utils - from isaaclab.assets import AssetBaseCfg - from isaaclab.scene import InteractiveScene, InteractiveSceneCfg - from isaaclab.utils.configclass import configclass - from isaaclab_assets.robots.cartpole import CARTPOLE_CFG +Each backend ships a small adapter class — its *replicate context* — that +knows how to take a registered cfg and replicate it on the backend's specific +runtime: +.. code-block:: text - @configclass - class MySceneCfg(InteractiveSceneCfg): - # Cloned once per environment. - robot = CARTPOLE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + UsdReplicateContext # replicates USD prim subtrees + PhysxReplicateContext # replicates PhysX rigid bodies and articulations + NewtonReplicateContext # replicates Newton bodies in its parallel pipeline - # Authored once globally, not cloned per environment. - light = AssetBaseCfg( - prim_path="/World/Light", - spawn=sim_utils.DistantLightCfg(intensity=3000.0), - ) +A single asset can register more than one context — a PhysX articulation +registers a PhysX context and a USD context so physics and visuals both follow, +a Newton articulation registers a Newton context plus a USD context only if it +owns visual prims. This is where backend differences are absorbed: swapping a +scene from PhysX to Newton swaps which context an asset registers with, while +the cfgs and the rest of the user code stay unchanged. +Running replication +~~~~~~~~~~~~~~~~~~~ - scene_cfg = MySceneCfg(num_envs=128, env_spacing=2.0, replicate_physics=True) - scene = InteractiveScene(cfg=scene_cfg) - -For heterogeneous scenes, use :class:`~isaaclab.sim.spawners.wrappers.MultiAssetSpawnerCfg` -or :class:`~isaaclab.sim.spawners.wrappers.MultiUsdFileCfg`. ``InteractiveScene`` assigns -representative source paths to the spawner and lets the clone strategy choose which -prototype each environment receives. See :doc:`multi_asset_spawning` for the asset -configuration details. +:func:`~isaaclab.cloner.replicate` is what actually runs the registered work. +The dispatch shape is roughly: -The most important scene options are on :class:`~isaaclab.scene.InteractiveSceneCfg`: +.. code-block:: python -.. list-table:: - :header-rows: 1 - :widths: 25 15 60 + def replicate(plan, stage): + for context_cls, rows in group_queue_by_context(plan): + context_cls().replicate(rows=rows, stage=stage) + publish(plan) - * - Field - - Default - - When to change it - * - ``replicate_physics`` - - ``True`` - - Keep enabled for homogeneous environments and fast startup. Disable it when each - environment needs independently authored physics or USD randomization. - * - ``filter_collisions`` - - ``True`` - - Keep enabled for parallel RL so cloned environments do not collide with each other. - This is automatic for PhysX-backed scene cloning. - * - ``clone_in_fabric`` - - ``False`` - - Enables the PhysX Fabric cloning path for faster scene creation. Use USDRT for stage - inspection when Fabric cloning is enabled. - - -Choosing an API ---------------- +Contexts run in a priority order that puts physics ahead of visuals, and the +plan is published to :class:`~isaaclab.sim.SimulationContext` so the rest of the +framework can read the per-env layout back. -.. list-table:: - :header-rows: 1 - :widths: 25 45 30 - - * - Goal - - Recommended API - - Notes - * - Build a custom cloning pipeline - - :func:`~isaaclab.cloner.usd_replicate` and a backend physics replicate function - - Useful for tests, tooling, or advanced scene construction. - * - Build complex direct mappings - - :func:`~isaaclab.cloner.make_clone_plan` - - Produces the same ``sources``, ``destinations``, and ``clone_mask`` used by direct cloning. - * - Build normal task scenes - - :class:`~isaaclab.scene.InteractiveScene` - - Preferred path. Configure assets with ``{ENV_REGEX_NS}`` and let the scene clone them. - * - Randomize which asset each environment receives - - ``InteractiveScene`` with :class:`~isaaclab.sim.spawners.wrappers.MultiAssetSpawnerCfg` or - :class:`~isaaclab.sim.spawners.wrappers.MultiUsdFileCfg` - - See :doc:`multi_asset_spawning` for the asset configuration details. - * - Use Isaac Sim's ``GridCloner`` - - Isaac Sim API - - Isaac Lab's tested path is the ``isaaclab.cloner`` API described here. - - -Migrating From Template Cloning -------------------------------- - -The template-root discovery API has been removed. Replace -``clone_from_template(...)`` calls with explicit source prims plus -:func:`~isaaclab.cloner.make_clone_plan`, a backend physics replicate function, and -:func:`~isaaclab.cloner.usd_replicate`. Replace ``TemplateCloneCfg`` with -:class:`~isaaclab.cloner.CloneCfg` for execution settings such as clone strategy, -Fabric cloning, and backend replication. - - -Collision Filtering and Isolation ---------------------------------- +Collision Filtering +------------------- -Some prims, such as terrain, are intentionally shared across environments and should collide -with every environment. These are modeled as global collision paths. The workaround is only -the per-environment filtering: when cloning is fully isolated per world, cloned environments -should not collide with each other and no manual per-environment filter should be needed. -Some PhysX cloning paths still rely on USD collision groups for that isolation fallback. In -the scene workflow this is handled by ``InteractiveScene`` when ``filter_collisions=True`` -and the backend is PhysX. +PhysX models per-env isolation through collision groups, so PhysX scenes need a +filtering pass after cloning to keep envs from colliding with each other while +still letting them collide with global prims (terrain, ground planes, lights). -For direct PhysX usage, call :func:`~isaaclab.cloner.filter_collisions` after cloning if -per-environment isolation is not already provided by the cloning backend: +:class:`~isaaclab.scene.InteractiveScene` runs that pass automatically when +``filter_collisions=True`` and the backend is PhysX. For direct PhysX pipelines, +call :func:`~isaaclab.cloner.filter_collisions` after the replicate: .. code-block:: python @@ -362,39 +373,4 @@ per-environment isolation is not already provided by the cloning backend: global_paths=["/World/ground"], ) -.. note:: - - Collision filtering uses PhysX collision groups. Newton handles per-environment isolation - through its own world system. - - -Backend and Option Notes ------------------------- - -**Physics replication.** :class:`~isaaclab.scene.InteractiveScene` selects the backend -replication function automatically. Direct PhysX users call -:func:`~isaaclab_physx.cloner.physx_replicate`; Newton users call -:func:`~isaaclab_newton.cloner.newton_physics_replicate`. - -**``replicate_physics=False``.** Disable physics replication when environments need -independent authored USD or physics state, such as some scale, texture, or color -randomization workflows. Startup and physics parsing are slower because the backend cannot -assume every environment is a clone of the same source. - -**``copy_from_source``.** ``InteractiveScene`` calls -``clone_environments(copy_from_source=True)`` when ``replicate_physics=False``. This skips -backend physics replication and leaves physics parsing to the backend. Spawner-level -``copy_from_source`` is a separate setting used by spawn functions that clone from a source -path matched by a regex. - -**Fabric cloning.** ``clone_in_fabric=True`` applies to PhysX replication. It can reduce -scene-creation time for large PhysX scenes, especially when many replicated rigid bodies are -authored. Fabric-backed stage data must be inspected through USDRT rather than normal USD -APIs. - - -See Also --------- - -* :doc:`multi_asset_spawning` -- configuring multi-asset and multi-USD spawners. -* :doc:`optimize_stage_creation` -- Fabric cloning and stage-in-memory optimizations. +Newton isolates envs through its world system and does not need this pass. diff --git a/docs/source/migration/migrating_from_isaacgymenvs.rst b/docs/source/migration/migrating_from_isaacgymenvs.rst index 2571f214a655..582667a91295 100644 --- a/docs/source/migration/migrating_from_isaacgymenvs.rst +++ b/docs/source/migration/migrating_from_isaacgymenvs.rst @@ -194,7 +194,7 @@ adding any other optional objects into the scene, such as lights. | self.up_axis = self.cfg["sim"]["up_axis"] | # add ground plane | | | spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg() | | self.sim = super().create_sim(self.device_id, self.graphics_device_id, | # clone, filter, and replicate | -| self.physics_engine, self.sim_params) | self.scene.clone_environments(copy_from_source=False) | +| self.physics_engine, self.sim_params) | # assets are built inside ReplicateSession | | self._create_ground_plane() | self.scene.filter_collisions(global_prim_paths=[]) | | self._create_envs(self.num_envs, self.cfg["env"]['envSpacing'], | # add articulation to scene | | int(np.sqrt(self.num_envs))) | self.scene.articulations["cartpole"] = self.cartpole | @@ -369,16 +369,15 @@ Isaac Lab eliminates the need for looping through the environments by using the The scene creation process is as follow: #. Construct a single environment (what the scene would look like if number of environments = 1) -#. Call ``clone_environments()`` to replicate the single environment +#. Use ``cloner.ReplicateSession`` to replicate the single environment #. Call ``filter_collisions()`` to filter out collision between environments (if required) .. code-block:: python - # construct a single environment with the Cartpole robot - self.cartpole = Articulation(self.cfg.robot_cfg) - # clone the environment - self.scene.clone_environments(copy_from_source=False) + # construct and replicate a single environment with the Cartpole robot + with cloner.ReplicateSession(): + self.cartpole = Articulation(self.cfg.robot_cfg) # filter collisions self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) @@ -660,8 +659,8 @@ the need to set simulation parameters for actors in the task implementation. | | spawn_ground_plane(prim_path="/World/ground", | | self.sim = super().create_sim(self.device_id, | cfg=GroundPlaneCfg()) | | self.graphics_device_id, self.physics_engine, | # clone, filter, and replicate | -| self.sim_params) | self.scene.clone_environments( | -| self._create_ground_plane() | copy_from_source=False) | +| self.sim_params) | # assets are built inside ReplicateSession | +| self._create_ground_plane() | | | self._create_envs(self.num_envs, | self.scene.filter_collisions( | | self.cfg["env"]['envSpacing'], | global_prim_paths=[]) | | int(np.sqrt(self.num_envs))) | # add articulation to scene | diff --git a/docs/source/migration/migrating_from_omniisaacgymenvs.rst b/docs/source/migration/migrating_from_omniisaacgymenvs.rst index 81369964dece..740ebe346bca 100644 --- a/docs/source/migration/migrating_from_omniisaacgymenvs.rst +++ b/docs/source/migration/migrating_from_omniisaacgymenvs.rst @@ -216,7 +216,7 @@ will automatically be created for the actor. This avoids the need to separately | super().set_up_scene(scene) | # add ground plane | | | spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg() | | self._cartpoles = ArticulationView( | # clone, filter, and replicate | -| prim_paths_expr="/World/envs/.*/Cartpole", | self.scene.clone_environments(copy_from_source=False) | +| prim_paths_expr="/World/envs/.*/Cartpole", | # assets are built inside ReplicateSession | | name="cartpole_view", reset_xform_properties=False | self.scene.filter_collisions(global_prim_paths=[]) | | ) | # add articulation to scene | | scene.add(self._cartpoles) | self.scene.articulations["cartpole"] = self.cartpole | @@ -633,8 +633,8 @@ Adding actors to the scene has been replaced by ``self.scene.articulations["cart | super().set_up_scene(scene) | spawn_ground_plane(prim_path="/World/ground", | | self._cartpoles = ArticulationView( | cfg=GroundPlaneCfg()) | | prim_paths_expr="/World/envs/.*/Cartpole", | # clone, filter, and replicate | -| name="cartpole_view", | self.scene.clone_environments( | -| reset_xform_properties=False | copy_from_source=False) | +| name="cartpole_view", | # assets are built inside ReplicateSession | +| reset_xform_properties=False | | | ) | self.scene.filter_collisions( | | scene.add(self._cartpoles) | global_prim_paths=[]) | | return | # add articulation to scene | diff --git a/docs/source/setup/walkthrough/api_env_design.rst b/docs/source/setup/walkthrough/api_env_design.rst index a669bc47fa1c..9e35e2d4bcd4 100644 --- a/docs/source/setup/walkthrough/api_env_design.rst +++ b/docs/source/setup/walkthrough/api_env_design.rst @@ -96,13 +96,12 @@ Next, let's take a look at the contents of the other python file in our task dir . . . def _setup_scene(self): - self.robot = Articulation(self.cfg.robot_cfg) - # add ground plane - spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) + with cloner.ReplicateSession(): + self.robot = Articulation(self.cfg.robot_cfg) + # add ground plane + spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) # add articulation to scene self.scene.articulations["robot"] = self.robot - # clone and replicate - self.scene.clone_environments(copy_from_source=False) # add lights light_cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75)) light_cfg.func("/World/Light", light_cfg) @@ -143,7 +142,7 @@ When the environment is initialized, it receives its own config as an argument, to initialize the ``DirectRLEnv``. This super call also calls ``_setup_scene``, which actually constructs the scene and clones it appropriately. Notably is how the robot is created and registered to the scene in ``_setup_scene``. First, the robot articulation is created by using the ``robot_config`` we defined in ``IsaacLabTutorialEnvCfg``: it doesn't exist before this point! When the -articulation is created, the robot exists on the stage at ``/World/envs/env_0/Robot``. The call to ``scene.clone_environments`` then +articulation is created, the robot exists on the stage at ``/World/envs/env_0/Robot``. The call to ``cloner.ReplicateSession`` then copies ``env_0`` appropriately. At this point the robot exists as many copies on the stage, so all that's left is to notify the ``scene`` object of the existence of this articulation to be tracked. The articulations of the scene are kept as a dictionary, so ``scene.articulations["robot"] = self.robot`` creates a new ``robot`` element of the ``articulations`` dictionary and sets the value to be ``self.robot``. diff --git a/docs/source/setup/walkthrough/technical_env_design.rst b/docs/source/setup/walkthrough/technical_env_design.rst index 41b99445c135..62a086343f9c 100644 --- a/docs/source/setup/walkthrough/technical_env_design.rst +++ b/docs/source/setup/walkthrough/technical_env_design.rst @@ -105,11 +105,10 @@ replace the contents of the ``__init__`` and ``_setup_scene`` methods with the f self.dof_idx, _ = self.robot.find_joints(self.cfg.dof_names) def _setup_scene(self): - self.robot = Articulation(self.cfg.robot_cfg) - # add ground plane - spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + with cloner.ReplicateSession(): + self.robot = Articulation(self.cfg.robot_cfg) + # add ground plane + spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) # add articulation to scene self.scene.articulations["robot"] = self.robot # add lights diff --git a/docs/source/setup/walkthrough/training_jetbot_gt.rst b/docs/source/setup/walkthrough/training_jetbot_gt.rst index 05e89ef45644..f49cc9e7d45c 100644 --- a/docs/source/setup/walkthrough/training_jetbot_gt.rst +++ b/docs/source/setup/walkthrough/training_jetbot_gt.rst @@ -67,11 +67,10 @@ Next, we need to expand the initialization and setup steps to construct the data .. code-block:: python def _setup_scene(self): - self.robot = Articulation(self.cfg.robot_cfg) - # add ground plane - spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + with cloner.ReplicateSession(): + self.robot = Articulation(self.cfg.robot_cfg) + # add ground plane + spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) # add articulation to scene self.scene.articulations["robot"] = self.robot # add lights diff --git a/scripts/demos/pick_and_place.py b/scripts/demos/pick_and_place.py index d5e77aa4a12a..aa99cb1480fd 100644 --- a/scripts/demos/pick_and_place.py +++ b/scripts/demos/pick_and_place.py @@ -35,6 +35,7 @@ import omni import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import ( Articulation, ArticulationCfg, @@ -221,8 +222,10 @@ def _setup_scene(self): self.gripper = SurfaceGripper(self.cfg.gripper) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # add articulation to scene self.scene.articulations["pick_and_place"] = self.pick_and_place self.scene.rigid_objects["cube"] = self.cube diff --git a/scripts/tutorials/06_deploy/anymal_c_env.py b/scripts/tutorials/06_deploy/anymal_c_env.py index 302fba78faa1..2f0003fcfe23 100644 --- a/scripts/tutorials/06_deploy/anymal_c_env.py +++ b/scripts/tutorials/06_deploy/anymal_c_env.py @@ -12,6 +12,7 @@ import warp as wp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sensors import ContactSensor, RayCaster @@ -63,7 +64,10 @@ def _setup_scene(self): self.cfg.terrain.num_envs = self.scene.cfg.num_envs self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing self._terrain = self.cfg.terrain.class_type(self.cfg.terrain) - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) light_cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75)) diff --git a/source/isaaclab/changelog.d/replication-session-redesign.minor.rst b/source/isaaclab/changelog.d/replication-session-redesign.minor.rst new file mode 100644 index 000000000000..598ceefabb2a --- /dev/null +++ b/source/isaaclab/changelog.d/replication-session-redesign.minor.rst @@ -0,0 +1,49 @@ +Added +^^^^^ + +* Added :data:`~isaaclab.cloner.REPLICATION_QUEUE` and the free function + :func:`~isaaclab.cloner.replicate`, the explicit registry-and-drain pair + that backends now hook into for replication. +* Added :meth:`~isaaclab.cloner.ClonePlan.from_env_0` for direct envs that + clone a single env-0 prototype across every env. +* Added :attr:`~isaaclab.cloner.CloneCfg.clone_regex` as the single source + of truth for the env-namespace convention (default ``"/World/envs/env_.*"``). + +Fixed +^^^^^ + +* Fixed :data:`~isaaclab.cloner.REPLICATION_QUEUE` leaking stale entries + when a backend or asset construction raised mid-session. + +Changed +^^^^^^^ + +* **Breaking:** Rewrote :class:`~isaaclab.cloner.ReplicateSession` as a thin + context manager around :func:`~isaaclab.cloner.make_clone_plan` and + :func:`~isaaclab.cloner.replicate`. The no-arg form and the cached + ``plan`` / ``cfg_rows`` / ``replicate_on_exit`` fields are gone. Direct + envs migrate to ``cloner.replicate(cloner.ClonePlan.from_env_0(...))``. +* **Breaking:** Changed :func:`~isaaclab.cloner.make_clone_plan` to take + ``cfgs`` and absorb the cfg-driven planning logic previously inside + :class:`~isaaclab.scene.InteractiveScene`, returning a self-contained + :class:`~isaaclab.cloner.ClonePlan`. +* **Breaking:** :func:`~isaaclab.cloner.replicate` and + :class:`~isaaclab.cloner.ReplicateSession` now require an explicit + ``stage=`` keyword; the :class:`~isaaclab.cloner.ClonePlan` is + stage-agnostic. +* Changed :attr:`~isaaclab.scene.InteractiveScene.env_origins` to read from + the published :class:`~isaaclab.cloner.ClonePlan`, making the plan the + single source of truth for env placement. + +Removed +^^^^^^^ + +* **Breaking:** Removed ``isaaclab.cloner.replicate_session_defaults`` and + ``isaaclab.cloner.replicate_session``. Use + :data:`~isaaclab.cloner.REPLICATION_QUEUE` and + :func:`~isaaclab.cloner.replicate` instead. +* **Breaking:** Removed :meth:`InteractiveScene.clone_environments`; direct + envs should use ``cloner.replicate(cloner.ClonePlan.from_env_0(...))``. +* **Breaking:** Removed :attr:`InteractiveScene.env_ns` and + :attr:`InteractiveScene.env_regex_ns`; read + :attr:`~isaaclab.cloner.CloneCfg.clone_regex` instead. diff --git a/source/isaaclab/isaaclab/cloner/__init__.pyi b/source/isaaclab/isaaclab/cloner/__init__.pyi index 348294dc1c12..0c6cf700d189 100644 --- a/source/isaaclab/isaaclab/cloner/__init__.pyi +++ b/source/isaaclab/isaaclab/cloner/__init__.pyi @@ -8,22 +8,40 @@ __all__ = [ "ClonePlan", "disabled_fabric_change_notifies", "filter_collisions", + "get_suffix", "grid_transforms", + "iter_clone_plan_matches", "make_clone_plan", "random", + "ReplicateSession", + "REPLICATION_QUEUE", + "replicate", "resolve_clone_plan_source", + "queue_usd_replication", "sequential", + "UsdReplicateContext", "usd_replicate", ] from .clone_plan import ClonePlan from .cloner_cfg import CloneCfg from .cloner_strategies import random, sequential +from ._fabric_notices import disabled_fabric_change_notifies from .cloner_utils import ( - disabled_fabric_change_notifies, filter_collisions, + get_suffix, grid_transforms, + iter_clone_plan_matches, make_clone_plan, resolve_clone_plan_source, +) +from .replicate_session import ( + REPLICATION_QUEUE, + ReplicateSession, + replicate, +) +from .usd import ( + UsdReplicateContext, + queue_usd_replication, usd_replicate, ) diff --git a/source/isaaclab/isaaclab/cloner/_fabric_notices.py b/source/isaaclab/isaaclab/cloner/_fabric_notices.py index 4326f4ae3195..b3557ef4bd41 100644 --- a/source/isaaclab/isaaclab/cloner/_fabric_notices.py +++ b/source/isaaclab/isaaclab/cloner/_fabric_notices.py @@ -17,9 +17,13 @@ from __future__ import annotations +import contextlib import ctypes import logging import threading +from collections.abc import Iterator + +from pxr import Usd, UsdUtils logger = logging.getLogger(__name__) @@ -149,3 +153,57 @@ def get_bindings() -> FabricNoticeBindings | None: return None _BINDINGS = b return _BINDINGS + + +@contextlib.contextmanager +def disabled_fabric_change_notifies(stage: Usd.Stage, *, restore: bool = True) -> Iterator[None]: + """Suspend Fabric's USD notice listener for the body of the ``with`` block. + + The listener is a global ``TfNotice`` that fires on every ``Sdf.CopySpec`` during + cloning; toggling it off via ``IFabricUsd::setEnableChangeNotifies`` skips the + per-spec Fabric sync that dominates cloning time for large PhysX rigid-body scenes. + Same toggle that :meth:`isaacsim.core.cloner.Cloner.disable_change_listener` flips, + called directly through Carbonite so we don't take an + ``isaacsim.core.simulation_manager`` dependency. + + Falls through to a no-op if the Carbonite interface can't be acquired (e.g. outside + a live Kit application). + + Args: + stage: USD stage whose Fabric notice handler should be suspended. + restore: When ``True`` (default), re-enable the handler on exit. Set to + ``False`` if a downstream Fabric resync is about to happen anyway (e.g. + right before ``sim.reset()``), to avoid a redundant re-enable. + + Yields: + None. + """ + bindings = get_bindings() + if bindings is None: + yield + return + + # usdrt only works with a live Kit app — defer import so module load stays cheap. + import usdrt + + # Avoid leaking a strong reference into the global ``StageCache`` for stages we did not + # author into the cache: ``Insert`` keeps the stage alive for the rest of the process. + cache = UsdUtils.StageCache.Get() + cached_id = cache.GetId(stage) + stage_id = cached_id.ToLongInt() if cached_id.IsValid() else cache.Insert(stage).ToLongInt() + # ``FabricId`` wraps a uint64; the C ABI needs the raw integer. + fabric_id = usdrt.Usd.Stage.Attach(stage_id).GetFabricId().id + # First-call ABI sanity check — if the toggle doesn't actually round-trip the flag + # (e.g. Kit's vtable shifted), fall through to a no-op rather than corrupting state. + if not bindings.validate_with(fabric_id): + logger.warning("Fabric notice toggle failed round-trip check — suspension disabled") + yield + return + was_enabled = bindings.is_enabled(fabric_id) + if was_enabled: + bindings.set_enable(fabric_id, False) + try: + yield + finally: + if restore and was_enabled: + bindings.set_enable(fabric_id, True) diff --git a/source/isaaclab/isaaclab/cloner/clone_plan.py b/source/isaaclab/isaaclab/cloner/clone_plan.py index 973122e7744b..62dbb3d6246a 100644 --- a/source/isaaclab/isaaclab/cloner/clone_plan.py +++ b/source/isaaclab/isaaclab/cloner/clone_plan.py @@ -5,29 +5,73 @@ from __future__ import annotations -from dataclasses import dataclass +from dataclasses import dataclass, field import torch @dataclass(frozen=True, eq=False) class ClonePlan: - """Flat cloning source of truth. - - Produced by scene planning after representative source prims are assigned. The - three fields are the same flat replication contract consumed by USD, physics, - and downstream scene-data providers: each source path maps to the destination - template at the same index, and :attr:`clone_mask` selects the environments - populated from that source. - """ + """Description of a single replication layout, consumed by :func:`~isaaclab.cloner.replicate`.""" sources: tuple[str, ...] - """Source prim paths used for replication.""" + """Source prim paths, one per replication row.""" destinations: tuple[str, ...] - """Destination path templates, one per source path.""" + """Destination path templates with ``"{}"`` for the env id, one per row.""" clone_mask: torch.Tensor - """Boolean tensor of shape ``[len(sources), num_envs]``; - ``clone_mask[i, j]`` is ``True`` if env ``j`` was populated from - :attr:`sources` ``[i]``.""" + """Bool tensor ``[len(sources), num_clones]``; ``True`` if env ``j`` comes from row ``i``.""" + + env_ids: torch.Tensor | None = None + """Long tensor ``[num_clones]`` of target env ids. + + Optional for plans used only with :func:`~isaaclab.cloner.iter_clone_plan_matches` or + :func:`~isaaclab.cloner.resolve_clone_plan_source`; required by :func:`~isaaclab.cloner.replicate`. + """ + + positions: torch.Tensor | None = None + """Per-env world positions [m], shape ``[num_clones, 3]``, or ``None``.""" + + cfg_rows: dict[int, tuple[int, ...]] = field(default_factory=dict) + """``id(cfg)`` to the row indices the cfg owns.""" + + @classmethod + def from_env_0( + cls, + source: str, + destination: str, + num_clones: int, + device: str, + positions: torch.Tensor | None = None, + ) -> ClonePlan: + """Build a single-source clone plan that targets every env from one source row. + + Auto-populates :attr:`cfg_rows` from + :data:`~isaaclab.cloner.REPLICATION_QUEUE`, including only cfgs whose + ``prim_path`` falls under the env-root prefix of ``destination``. Must be + called *after* all asset constructors have run, so their replication entries + are already in the queue; otherwise those assets will be skipped by the + subsequent :func:`~isaaclab.cloner.replicate` call. + + Args: + source: Source prim path (typically ``/World/envs/env_0``). + destination: Destination template with ``"{}"`` for the env id. + num_clones: Number of target envs. + device: Torch device for the mask and env id buffers. + positions: Optional per-env world positions [m], shape ``[num_clones, 3]``. + """ + from .replicate_session import REPLICATION_QUEUE # noqa: PLC0415 + + prefix, _, _ = destination.partition("{}") + cfg_rows: dict[int, tuple[int, ...]] = { + id(cfg): (0,) for cfg, _ in REPLICATION_QUEUE if cfg.prim_path.startswith(prefix) + } + return cls( + sources=(source,), + destinations=(destination,), + clone_mask=torch.ones((1, num_clones), dtype=torch.bool, device=device), + env_ids=torch.arange(num_clones, dtype=torch.long, device=device), + positions=positions, + cfg_rows=cfg_rows, + ) diff --git a/source/isaaclab/isaaclab/cloner/cloner_cfg.py b/source/isaaclab/isaaclab/cloner/cloner_cfg.py index 477b4bbfc2c2..464794e366ac 100644 --- a/source/isaaclab/isaaclab/cloner/cloner_cfg.py +++ b/source/isaaclab/isaaclab/cloner/cloner_cfg.py @@ -5,6 +5,8 @@ from __future__ import annotations +from collections.abc import Callable + from isaaclab.utils.configclass import configclass from .cloner_strategies import random @@ -14,32 +16,15 @@ class CloneCfg: """Configuration for environment replication. - The scene builds a :class:`~isaaclab.cloner.ClonePlan` directly from asset - configuration, spawns the representative source prims, and then uses this - configuration to dispatch USD and physics replication for that plan. - """ - - clone_regex: str = "/World/envs/env_.*" - """Destination template for per-environment paths. - - The substring ``".*"`` is replaced with ``"{}"`` internally and formatted with the - environment index (e.g., ``/World/envs/env_0``, ``/World/envs/env_1``). + Holds the knobs :class:`~isaaclab.scene.InteractiveScene` forwards to + :func:`~isaaclab.cloner.make_clone_plan` when building per-env layouts. """ - clone_usd: bool = True - """Enable USD-spec replication to author cloned prims and optional transforms.""" - - clone_physics: bool = True - """Enable PhysX replication for the same mapping to speed up physics setup.""" - - physics_clone_fn: callable | None = None - """Function used to perform physics replication.""" - - clone_strategy: callable = random + clone_strategy: Callable[..., object] = random """Function used to build prototype-to-environment mapping. Default is :func:`random`.""" device: str = "cpu" """Torch device on which mapping buffers are allocated.""" - clone_in_fabric: bool = False - """Enable/disable cloning in fabric for PhysX replication. Default is False.""" + clone_regex: str = "/World/envs/env_.*" + """Regex matching every replicated env prim. Used to expand ``{ENV_REGEX_NS}`` cfg macros.""" diff --git a/source/isaaclab/isaaclab/cloner/cloner_utils.py b/source/isaaclab/isaaclab/cloner/cloner_utils.py index 8b18b28664df..f7919f9b0084 100644 --- a/source/isaaclab/isaaclab/cloner/cloner_utils.py +++ b/source/isaaclab/isaaclab/cloner/cloner_utils.py @@ -3,21 +3,25 @@ # # SPDX-License-Identifier: BSD-3-Clause + from __future__ import annotations -import contextlib import itertools import logging import math import re -from collections.abc import Iterator, Sequence +from collections.abc import Callable, Iterable, Iterator +from typing import TYPE_CHECKING, Any import torch -from pxr import Gf, Sdf, Usd, UsdGeom, UsdUtils, Vt +from pxr import Sdf, Usd, UsdGeom -from . import _fabric_notices from .clone_plan import ClonePlan +from .cloner_strategies import sequential + +if TYPE_CHECKING: + pass logger = logging.getLogger(__name__) @@ -157,222 +161,152 @@ def iter_clone_plan_matches(plan: ClonePlan, path_expr: str) -> Iterator[tuple[s yield from (match for match in matches if len(match[1].format(match[3][0])) == owner_length) -@contextlib.contextmanager -def disabled_fabric_change_notifies(stage: Usd.Stage, *, restore: bool = True) -> Iterator[None]: - """Suspend the ``IFabricUsd`` USD notice listener for the body of the ``with`` block. - - Targets the same handler that :meth:`isaacsim.core.cloner.Cloner.disable_change_listener` - toggles, but goes through ``omni::fabric::IFabricUsd`` directly so we don't take an - ``isaacsim.core.simulation_manager`` dependency. - - The listener is a global ``TfNotice`` registered when ``omni.fabric`` loads; it - short-circuits via a soft flag (``IFabricUsd.cpp:739``). Toggling that flag is what - skips the per-``Sdf.CopySpec`` Fabric sync that dominates cloning time on large scenes. - - When this provides a measurable speedup - ---------------------------------------- - Bisection on the regression test (see ``test_cloner.py``) shows the listener cost is - only on the critical path when **all** of these hold: - - 1. The clone happens through the ``InteractiveScene`` path with ``replicate_physics=True``. - Calling :func:`usd_replicate` directly on a stage produces no measurable gap; with - ``replicate_physics=False`` the gap drops to ~1.19x. The PhysX replication path is - what amplifies per-spec listener work. - 2. The cloned prims carry PhysX rigid-body schemas (e.g. ``UsdPhysics.RigidBodyAPI``, - authored via ``rigid_props`` on a spawn cfg). Plain Xforms or geometry without - physics schemas produce ~1.0x — the listener has no Fabric-tracked state to sync. - ``mass_props`` and ``collision_props`` add nothing beyond ``rigid_props``. - 3. Total per-``Sdf.CopySpec`` firings reach ~32K — i.e. ``num_bodies × num_envs`` is - large enough to dominate scene-init cost. Below this the speedup sinks into noise. - - Conditions outside this envelope (no PhysX schemas, single-env scenes, raw - ``usd_replicate`` calls, ``replicate_physics=False``) won't see a perf win — the - suspension is correct but its effect is lost in the rest of the work. - - Re-entrant: if the flag is already off on entry, ``__exit__`` leaves it off. Falls - through to a no-op if the Carbonite interface can't be acquired (e.g. outside a live - Kit application) — the caller never breaks, it just doesn't get the perf win. - - Args: - stage: USD stage whose Fabric notice handler should be suspended. - restore: When ``True`` (default), re-enable the handler on exit. Set to ``False`` - inside a known clone-then-``sim.reset`` window where the downstream Fabric - resync happens anyway and re-enabling here would trigger a redundant - ``forceMinimalPopulate`` batch — see ``PluginInterface.cpp:337``. - - Yields: - None. - """ - bindings = _fabric_notices.get_bindings() - if bindings is None: - yield - return - - # usdrt only works with a live Kit app — defer import so module load stays cheap. - import usdrt - - # Avoid leaking a strong reference into the global ``StageCache`` for stages we did not - # author into the cache: ``Insert`` keeps the stage alive for the rest of the process. - cache = UsdUtils.StageCache.Get() - cached_id = cache.GetId(stage) - stage_id = cached_id.ToLongInt() if cached_id.IsValid() else cache.Insert(stage).ToLongInt() - # ``FabricId`` wraps a uint64; the C ABI needs the raw integer. - fabric_id = usdrt.Usd.Stage.Attach(stage_id).GetFabricId().id - # First-call ABI sanity check — if the toggle doesn't actually round-trip the flag - # (e.g. Kit's vtable shifted), fall through to a no-op rather than corrupting state. - if not bindings.validate_with(fabric_id): - logger.warning("Fabric notice toggle failed round-trip check — suspension disabled") - yield - return - was_enabled = bindings.is_enabled(fabric_id) - if was_enabled: - bindings.set_enable(fabric_id, False) - try: - yield - finally: - if restore and was_enabled: - bindings.set_enable(fabric_id, True) - - def make_clone_plan( - sources: Sequence[Sequence[str]], - destinations: Sequence[str], + cfgs: Iterable[Any], num_clones: int, - clone_strategy: callable, - device: str = "cpu", -) -> tuple[tuple[str, ...], tuple[str, ...], torch.Tensor]: - """Compute the flat source/destination/mask components of a clone plan. - - Enumerates all combinations of prototypes, selects a combination per environment using - ``clone_strategy``, and builds the boolean masking matrix that indicates which prototype - populates each environment slot. The caller composes the returned tuple into a - :class:`ClonePlan`. + env_spacing: float, + device: str, + *, + clone_strategy: Callable = sequential, + valid_set: torch.Tensor | None = None, +) -> ClonePlan: + """Build a :class:`~isaaclab.cloner.ClonePlan` from asset cfgs. + + Iterates ``cfgs``, identifies env-scoped cfgs with a spawn, expands + :class:`~isaaclab.sim.MultiAssetSpawnerCfg` / :class:`~isaaclab.sim.MultiUsdFileCfg` + into per-variant prototype rows, runs ``clone_strategy`` to assign prototypes to + envs, and returns a self-contained :class:`ClonePlan` with ``cfg_rows`` populated. + + Each input cfg's ``spawn_path`` / ``spawn_paths`` is mutated so the subsequent + asset constructor spawns the prototype into its first active environment. Cfgs + whose ``prim_path`` is global (not under the env root ``/World/envs/``) or that + lack a spawn are skipped — they do not appear in the plan and are not replicated. Args: - sources: Prototype prim paths grouped by asset type (e.g., ``[[robot_a, robot_b], [obj_x]]``). - destinations: Destination path templates (one per group) with ``"{}"`` placeholder for env id. - num_clones: Number of environments to populate. - clone_strategy: Function that picks a prototype combo per environment; signature - ``clone_strategy(combos: Tensor, num_clones: int, device: str) -> Tensor[num_clones, num_groups]``. - device: Torch device for the returned mask. Defaults to ``"cpu"``. + cfgs: Asset cfgs with resolved ``prim_path`` (no ``{ENV_REGEX_NS}`` macros). + num_clones: Number of target envs. + env_spacing: Distance between neighboring grid env origins [m]. + device: Torch device for plan tensors. + clone_strategy: Function that assigns prototype combinations to envs. Defaults + to :func:`~isaaclab.cloner.sequential`. + valid_set: Optional ``[num_combos, num_groups]`` long tensor of valid prototype + combinations. ``None`` (default) uses the full cartesian product of every + group's prototype indices. Returns: - A tuple ``(sources, destinations, clone_mask)`` where ``sources`` and ``destinations`` - are flattened per-source entries (one entry per prototype) and ``clone_mask`` is a - ``[num_src, num_clones]`` boolean tensor on ``device``. + A :class:`ClonePlan` whose ``sources``/``destinations``/``clone_mask`` describe + the flat prototype-to-env mapping and whose ``cfg_rows`` maps each cfg to the + rows it owns. """ - if len(sources) != len(destinations): - raise ValueError(f"Expected one destination per source group, got {len(destinations)} and {len(sources)}.") - if not sources: - raise ValueError("Expected at least one source group.") - group_sizes = [len(group) for group in sources] - if any(size == 0 for size in group_sizes): - raise ValueError("Source groups must not be empty.") - - # 1) Flatten into src and dest lists - src = tuple(p for group in sources for p in group) - dest = tuple(dst for dst, group in zip(destinations, sources) for _ in group) - - # 2) Enumerate all combinations of "one prototype per group" - # all_combos: list of tuples (g0_idx, g1_idx, ..., g_{G-1}_idx) - all_combos = list(itertools.product(*[range(s) for s in group_sizes])) - combos = torch.tensor(all_combos, dtype=torch.long, device=device) - - # 3) Assign a combination to each environment + import isaaclab.sim as sim_utils # noqa: PLC0415 + + def num_variants(spawn_cfg: Any) -> int: + if isinstance(spawn_cfg, sim_utils.MultiAssetSpawnerCfg): + return len(spawn_cfg.assets_cfg) + if isinstance(spawn_cfg, sim_utils.MultiUsdFileCfg): + return 1 if isinstance(spawn_cfg.usd_path, str) else len(spawn_cfg.usd_path) + return 1 + + def set_spawn_paths(spawn_cfg: Any, paths: list[str | None]) -> None: + if isinstance(spawn_cfg, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg)): + spawn_cfg.spawn_paths = paths + else: + active = [p for p in paths if p is not None] + if len(active) != 1: + raise ValueError("Single spawner expects exactly one planned source path.") + spawn_cfg.spawn_path = active[0] + + env_root_marker = "/World/envs/" + env_template = "/World/envs/env_{}" + + # 1) Build per-group records: (cfg, spawn_cfg, destination_template, num_variants). + groups: list[tuple[Any, Any, str, int]] = [] + for cfg in cfgs: + if not hasattr(cfg, "prim_path") or not hasattr(cfg, "spawn") or cfg.spawn is None: + continue + prim_path = cfg.prim_path + if env_root_marker not in prim_path: + continue + count = num_variants(cfg.spawn) + if count <= 0: + raise ValueError(f"Spawner at '{prim_path}' must have at least one variant.") + destination = prim_path.replace(".*", "{}") + groups.append((cfg, cfg.spawn, destination, count)) + + env_ids = torch.arange(num_clones, dtype=torch.long, device=device) + positions, _ = grid_transforms(num_clones, env_spacing, device=device) + + # 2) No env-scoped cfgs: emit an empty plan so the scene can still proceed. + if not groups: + empty_mask = torch.zeros((0, num_clones), dtype=torch.bool, device=device) + return ClonePlan( + sources=(), + destinations=(), + clone_mask=empty_mask, + env_ids=env_ids, + positions=positions, + cfg_rows={}, + ) + + # 3) Homogeneous (every cfg is single-variant): emit the simpler env-root plan. + if all(count == 1 for _, _, _, count in groups): + for cfg, spawn_cfg, destination, _ in groups: + set_spawn_paths(spawn_cfg, [destination.format(0)]) + cfg_rows = {id(cfg): (0,) for cfg, _, _, _ in groups} + return ClonePlan( + sources=(env_template.format(0),), + destinations=(env_template,), + clone_mask=torch.ones((1, num_clones), dtype=torch.bool, device=device), + env_ids=env_ids, + positions=positions, + cfg_rows=cfg_rows, + ) + + # 4) Heterogeneous: enumerate prototype combos, build per-row mask, mutate spawn paths. + group_sizes = [count for _, _, _, count in groups] + if valid_set is None: + all_combos = list(itertools.product(*[range(s) for s in group_sizes])) + combos = torch.tensor(all_combos, dtype=torch.long, device=device) + else: + combos = valid_set.to(device=device, dtype=torch.long) chosen = clone_strategy(combos, num_clones, device) - # 4) Build masking: [num_src, num_clones] boolean - # For each env, for each group, mark exactly one prototype row as True. group_offsets = torch.tensor([0] + list(itertools.accumulate(group_sizes[:-1])), dtype=torch.long, device=device) rows = (chosen + group_offsets).view(-1) cols = torch.arange(num_clones, device=device).view(-1, 1).expand(-1, len(group_sizes)).reshape(-1) - masking = torch.zeros((sum(group_sizes), num_clones), dtype=torch.bool, device=device) - masking[rows, cols] = True - return src, dest, masking - - -def usd_replicate( - stage: Usd.Stage, - sources: Sequence[str], - destinations: Sequence[str], - env_ids: torch.Tensor, - mask: torch.Tensor | None = None, - positions: torch.Tensor | None = None, - quaternions: torch.Tensor | None = None, -) -> None: - """Replicate USD prims to per-environment destinations. - - Copies each source prim spec to destination templates for selected environments - (``mask``). Optionally authors translate/orient from position/quaternion buffers. - Replication runs in path-depth order (parents before children) for robust composition. - - Args: - stage: USD stage. - sources: Source prim paths. - destinations: Destination formattable templates with ``"{}"`` for env index. - env_ids: Environment indices. - mask: Optional per-source or shared mask. ``None`` selects all. - positions: Optional positions (``[E, 3]``) -> ``xformOp:translate``. - quaternions: Optional orientations (``[E, 4]``) in ``xyzw`` -> ``xformOp:orient``. - - """ - rl = stage.GetRootLayer() - - # Group replication by destination path depth so ancestors land before deeper paths. - # This avoids composition issues for nested or interdependent specs. - def dp_depth(template: str) -> int: - """Return destination prim path depth for stable parent-first replication.""" - dp = template.format(0) - return Sdf.Path(dp).pathElementCount - - order = sorted(range(len(sources)), key=lambda i: dp_depth(destinations[i])) - - # Process in layers of equal depth, committing at each depth to stabilize composition - depth_to_indices: dict[int, list[int]] = {} - for i in order: - d = dp_depth(destinations[i]) - depth_to_indices.setdefault(d, []).append(i) - - for depth in sorted(depth_to_indices.keys()): - with Sdf.ChangeBlock(): - for i in depth_to_indices[depth]: - src = sources[i] - tmpl = destinations[i] - # Select target environments for this source (supports None, [E], or [S, E]) - target_envs = env_ids if mask is None else env_ids[mask[i]] - for wid in target_envs.tolist(): - dp = tmpl.format(wid) - Sdf.CreatePrimInLayer(rl, dp) - if src == dp: - pass # self-copy: CreatePrimInLayer already ensures it exists; CopySpec would be destructive - else: - Sdf.CopySpec(rl, Sdf.Path(src), rl, Sdf.Path(dp)) - - if positions is not None or quaternions is not None: - ps = rl.GetPrimAtPath(dp) - op_names = [] - if positions is not None: - p = positions[wid] - t_attr = ps.GetAttributeAtPath(dp + ".xformOp:translate") - if t_attr is None: - t_attr = Sdf.AttributeSpec(ps, "xformOp:translate", Sdf.ValueTypeNames.Double3) - t_attr.default = Gf.Vec3d(float(p[0]), float(p[1]), float(p[2])) - op_names.append("xformOp:translate") - if quaternions is not None: - q = quaternions[wid] - o_attr = ps.GetAttributeAtPath(dp + ".xformOp:orient") - if o_attr is None: - o_attr = Sdf.AttributeSpec(ps, "xformOp:orient", Sdf.ValueTypeNames.Quatd) - # xyzw convention: q[3] is w, q[0:3] is xyz - o_attr.default = Gf.Quatd(float(q[3]), Gf.Vec3d(float(q[0]), float(q[1]), float(q[2]))) - op_names.append("xformOp:orient") - # Only author xformOpOrder for the ops we actually authored - if op_names: - op_order = ps.GetAttributeAtPath(dp + ".xformOpOrder") or Sdf.AttributeSpec( - ps, UsdGeom.Tokens.xformOpOrder, Sdf.ValueTypeNames.TokenArray - ) - op_order.default = Vt.TokenArray(op_names) + num_rows = sum(group_sizes) + clone_mask = torch.zeros((num_rows, num_clones), dtype=torch.bool, device=device) + clone_mask[rows, cols] = True + + sources_list: list[str] = [] + destinations_list: list[str] = [] + cfg_rows: dict[int, tuple[int, ...]] = {} + row = 0 + for cfg, spawn_cfg, destination, count in groups: + cfg_rows[id(cfg)] = tuple(range(row, row + count)) + group_mask = clone_mask[row : row + count] + env_ids_assigned = group_mask.to(torch.int).argmax(dim=1).tolist() + active = group_mask.any(dim=1).tolist() + paths = [ + destination.format(env_id) if is_active else None for env_id, is_active in zip(env_ids_assigned, active) + ] + for i, path in enumerate(paths): + destinations_list.append(destination) + # Inactive prototypes fall back to env-i so the source path stays valid even + # when the variant has no active environment (matches the legacy behavior). + sources_list.append(path if path is not None else destination.format(i)) + set_spawn_paths(spawn_cfg, paths) + row += count + + return ClonePlan( + sources=tuple(sources_list), + destinations=tuple(destinations_list), + clone_mask=clone_mask, + env_ids=env_ids, + positions=positions, + cfg_rows=cfg_rows, + ) def filter_collisions( diff --git a/source/isaaclab/isaaclab/cloner/replicate_session.py b/source/isaaclab/isaaclab/cloner/replicate_session.py new file mode 100644 index 000000000000..d55c501b3bd9 --- /dev/null +++ b/source/isaaclab/isaaclab/cloner/replicate_session.py @@ -0,0 +1,135 @@ +# 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 + +"""Replication queue, :func:`replicate` drain, and :class:`ReplicateSession` sugar.""" + +from __future__ import annotations + +from collections.abc import Callable, Iterable +from typing import TYPE_CHECKING, Any + +from .cloner_strategies import sequential + +if TYPE_CHECKING: + import torch + + from pxr import Usd + + from .clone_plan import ClonePlan + + +REPLICATION_QUEUE: list[tuple[Any, type]] = [] +"""``(cfg, BackendCtxCls)`` pairs appended by ``queue__replication`` and drained by :func:`replicate`.""" + + +def replicate(plan: ClonePlan, *, stage: Usd.Stage) -> None: + """Drain :data:`REPLICATION_QUEUE` against ``plan``, dispatch each backend, publish the plan. + + Cfgs absent from ``plan.cfg_rows`` are silently skipped. Backend contexts run in + ascending ``replicate_priority`` order. The queue is cleared up front, so a backend + failure cannot leak stale entries into the next call. + """ + from isaaclab.sim import SimulationContext # noqa: PLC0415 + + queued = list(REPLICATION_QUEUE) + REPLICATION_QUEUE.clear() + + # Group queued cfgs by backend, taking the union of row indices each backend owns. + backend_rows: dict[type, set[int]] = {} + for cfg, BackendCtxCls in queued: + rows = plan.cfg_rows.get(id(cfg)) + if rows is None: + continue + backend_rows.setdefault(BackendCtxCls, set()).update(rows) + + backend_ctxs: dict[type, Any] = {} + for BackendCtxCls, row_set in backend_rows.items(): + ctx = BackendCtxCls(stage) + backend_ctxs[BackendCtxCls] = ctx + row_list = sorted(row_set) + ctx.queue_mapping( + [plan.sources[i] for i in row_list], + [plan.destinations[i] for i in row_list], + plan.env_ids, + plan.clone_mask[row_list], + positions=plan.positions, + ) + + for ctx in sorted(backend_ctxs.values(), key=lambda c: getattr(c, "replicate_priority", 0)): + ctx.replicate() + + SimulationContext.instance().set_clone_plan(plan) + + +class ReplicateSession: + """Folds :func:`make_clone_plan` and :func:`replicate` into a ``with`` block. + + ``__enter__`` builds the plan (and mutates each cfg's ``spawn_path``); asset + constructors inside the block register backend replication into + :data:`REPLICATION_QUEUE`; ``__exit__`` drains and dispatches. + + Example: + + .. code-block:: python + + with cloner.ReplicateSession(cfgs, num_clones=128, env_spacing=2.0, device="cuda:0", stage=sim.stage): + for cfg in cfgs: + cfg.class_type(cfg) + """ + + def __init__( + self, + cfgs: Iterable[Any], + num_clones: int, + env_spacing: float, + device: str, + *, + stage: Usd.Stage, + clone_strategy: Callable = sequential, + valid_set: torch.Tensor | None = None, + ): + """Capture arguments for :func:`make_clone_plan` and :func:`replicate`. + + Args: + cfgs: Asset cfgs with resolved ``prim_path``. + num_clones: Number of target envs. + env_spacing: Grid spacing between env origins [m]. + device: Torch device for plan tensors. + stage: USD stage to author replicated prim specs into. + clone_strategy: Prototype-to-env assignment function. + valid_set: Optional ``[num_combos, num_groups]`` long tensor of valid + prototype combinations; ``None`` uses the full cartesian product. + """ + self._cfgs = cfgs + self._stage = stage + self._kwargs = dict( + num_clones=num_clones, + env_spacing=env_spacing, + device=device, + clone_strategy=clone_strategy, + valid_set=valid_set, + ) + self._plan: ClonePlan | None = None + + def __enter__(self) -> ReplicateSession: + from .cloner_utils import make_clone_plan # noqa: PLC0415 + + self._plan = make_clone_plan(self._cfgs, **self._kwargs) + return self + + def __exit__(self, exc_type, exc_value, traceback) -> None: + if exc_type is None: + assert self._plan is not None + replicate(self._plan, stage=self._stage) + else: + # Drop cfgs registered before the failure so the next session is clean. + REPLICATION_QUEUE.clear() + + @property + def plan(self) -> ClonePlan: + """The :class:`~isaaclab.cloner.ClonePlan` produced in :meth:`__enter__`.""" + if self._plan is None: + raise RuntimeError("ReplicateSession.plan is only available inside the with block.") + return self._plan diff --git a/source/isaaclab/isaaclab/cloner/usd.py b/source/isaaclab/isaaclab/cloner/usd.py new file mode 100644 index 000000000000..ace2adffbcf0 --- /dev/null +++ b/source/isaaclab/isaaclab/cloner/usd.py @@ -0,0 +1,185 @@ +# 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 + +from __future__ import annotations + +from collections.abc import Sequence +from typing import Any + +import torch + +from pxr import Gf, Sdf, Usd, UsdGeom, Vt + +from ._fabric_notices import disabled_fabric_change_notifies +from .replicate_session import REPLICATION_QUEUE + + +def _select_env_ids(env_ids: torch.Tensor, mask: torch.Tensor | None, row: int) -> torch.Tensor: + """Return the environment ids selected by a replication row.""" + if mask is None: + return env_ids + row_mask = mask if mask.dim() == 1 else mask[row] + if row_mask.dtype != torch.bool: + row_mask = row_mask.to(dtype=torch.bool) + return env_ids[row_mask] + + +class UsdReplicateContext: + """Queue and apply USD replication work for one stage.""" + + replicate_priority = 100 + + def __init__(self, stage: Usd.Stage): + """Initialize the context. + + Args: + stage: USD stage to author replicated prim specs into. + """ + self.stage = stage + self._queue: list[tuple[str, str, torch.Tensor, torch.Tensor | None, torch.Tensor | None]] = [] + + def queue( + self, + source: str, + destination: str, + env_ids: torch.Tensor, + *, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + ) -> None: + """Queue one USD source row for replication. + + Args: + source: Source prim path. + destination: Destination path template with ``"{}"`` for env id. + env_ids: Environment ids selected for this source row. + positions: Optional per-environment world positions [m]. + quaternions: Optional per-environment orientations in xyzw order. + """ + self._queue.append((source, destination, env_ids, positions, quaternions)) + + def queue_mapping( + self, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mask: torch.Tensor | None = None, + *, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + ) -> None: + """Queue replication rows from the current flat clone mapping. + + Args: + sources: Source prim paths. + destinations: Destination path templates with ``"{}"`` for env id. + env_ids: Environment indices. + mask: Optional per-source or shared mask. + positions: Optional per-environment world positions [m]. + quaternions: Optional per-environment orientations in xyzw order. + """ + for i, source in enumerate(sources): + self.queue( + source, + destinations[i], + _select_env_ids(env_ids, mask, i), + positions=positions, + quaternions=quaternions, + ) + + def replicate(self) -> None: + """Apply all queued USD copy specs in parent-before-child order.""" + if not self._queue: + return + + # Suspend Fabric's per-Sdf.CopySpec notice listener for the duration of the copy work; + # no-op outside a live Kit application. + with disabled_fabric_change_notifies(self.stage): + self._apply_queue() + + def _apply_queue(self) -> None: + """Author the queued copy specs into the stage's root layer.""" + rl = self.stage.GetRootLayer() + + def dp_depth(template: str) -> int: + """Return destination prim path depth for stable parent-first replication.""" + dp = template.format(0) + return Sdf.Path(dp).pathElementCount + + depth_to_items: dict[int, list[tuple[str, str, torch.Tensor, torch.Tensor | None, torch.Tensor | None]]] = {} + for item in self._queue: + depth_to_items.setdefault(dp_depth(item[1]), []).append(item) + + for depth in sorted(depth_to_items.keys()): + with Sdf.ChangeBlock(): + for src, tmpl, target_envs, positions, quaternions in depth_to_items[depth]: + for wid in target_envs.tolist(): + wid = int(wid) + dp = tmpl.format(wid) + Sdf.CreatePrimInLayer(rl, dp) + if src != dp: + Sdf.CopySpec(rl, Sdf.Path(src), rl, Sdf.Path(dp)) + + if positions is not None or quaternions is not None: + ps = rl.GetPrimAtPath(dp) + op_names = [] + if positions is not None: + p = positions[wid] + t_attr = ps.GetAttributeAtPath(dp + ".xformOp:translate") + if t_attr is None: + t_attr = Sdf.AttributeSpec(ps, "xformOp:translate", Sdf.ValueTypeNames.Double3) + t_attr.default = Gf.Vec3d(float(p[0]), float(p[1]), float(p[2])) + op_names.append("xformOp:translate") + if quaternions is not None: + q = quaternions[wid] + o_attr = ps.GetAttributeAtPath(dp + ".xformOp:orient") + if o_attr is None: + o_attr = Sdf.AttributeSpec(ps, "xformOp:orient", Sdf.ValueTypeNames.Quatd) + o_attr.default = Gf.Quatd(float(q[3]), Gf.Vec3d(float(q[0]), float(q[1]), float(q[2]))) + op_names.append("xformOp:orient") + if op_names: + op_order = ps.GetAttributeAtPath(dp + ".xformOpOrder") or Sdf.AttributeSpec( + ps, UsdGeom.Tokens.xformOpOrder, Sdf.ValueTypeNames.TokenArray + ) + op_order.default = Vt.TokenArray(op_names) + + +def queue_usd_replication(cfg: Any) -> None: + """Register ``cfg`` for USD replication when :func:`~isaaclab.cloner.replicate` next runs. + + Appends ``(cfg, UsdReplicateContext)`` to :data:`~isaaclab.cloner.REPLICATION_QUEUE`. + The actual row resolution and dispatch happen inside :func:`~isaaclab.cloner.replicate`, + so this helper is safe to call from any asset constructor — no active session is required. + """ + REPLICATION_QUEUE.append((cfg, UsdReplicateContext)) + + +def usd_replicate( + stage: Usd.Stage, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mask: torch.Tensor | None = None, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, +) -> None: + """Replicate USD prims to per-environment destinations. + + Copies each source prim spec to destination templates for selected environments + (``mask``). Optionally authors translate/orient from position/quaternion buffers. + Replication runs in path-depth order (parents before children) for robust composition. + + Args: + stage: USD stage. + sources: Source prim paths. + destinations: Destination formattable templates with ``"{}"`` for env index. + env_ids: Environment indices. + mask: Optional per-source or shared mask. ``None`` selects all. + positions: Optional positions [m], shape ``[E, 3]``, authored as ``xformOp:translate``. + quaternions: Optional orientations in xyzw order, shape ``[E, 4]``, authored as ``xformOp:orient``. + """ + ctx = UsdReplicateContext(stage) + ctx.queue_mapping(sources, destinations, env_ids, mask, positions=positions, quaternions=quaternions) + ctx.replicate() diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 262511885f41..11df307b2356 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -36,7 +36,6 @@ from isaaclab.sim.utils.stage import get_current_stage, get_current_stage_id from isaaclab.sim.views import FrameView from isaaclab.terrains import TerrainImporter, TerrainImporterCfg -from isaaclab.utils.version import has_kit # Note: This is a temporary import for the VisuoTactileSensorCfg class. # It will be removed once the VisuoTactileSensor class is added to the core Isaac Lab framework. @@ -105,12 +104,20 @@ class MySceneCfg(InteractiveSceneCfg): robot = scene.articulations["robot"] If the :class:`InteractiveSceneCfg` class does not include asset entities, the cloning process - can still be triggered if assets were added to the stage outside of the :class:`InteractiveScene` class: + can still be triggered by constructing assets directly on the stage and then calling + :func:`isaaclab.cloner.replicate` with a single-source :class:`~isaaclab.cloner.ClonePlan`: .. code-block:: python + from isaaclab import cloner + from isaaclab.assets import Articulation + scene = InteractiveScene(cfg=InteractiveSceneCfg(num_envs=128, replicate_physics=True)) - scene.clone_environments() + robot = Articulation(robot_cfg) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(scene.num_envs, scene.cfg.env_spacing, device=scene.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, scene.num_envs, scene.device, pos) + cloner.replicate(plan, stage=scene.stage) .. note:: It is important to note that the scene only performs common operations on the entities. For example, @@ -146,196 +153,68 @@ def __init__(self, cfg: InteractiveSceneCfg): self.stage_id = get_current_stage_id() self.physics_backend = self.sim.physics_manager.__name__.lower() requested_viz_types = set(self.sim.resolve_visualizer_types()) - if self.physics_backend.startswith("ovphysx"): - from isaaclab_ovphysx.cloner import ovphysx_replicate - - physics_clone_fn = ovphysx_replicate - elif self.physics_backend.startswith("physx"): - from isaaclab_physx.cloner import physx_replicate - - physics_clone_fn = physx_replicate - elif self.physics_backend.startswith("newton"): - from isaaclab_newton.cloner import newton_physics_replicate - - physics_clone_fn = newton_physics_replicate - else: - raise ValueError(f"Unsupported physics backend: {self.physics_backend}") # physics scene path self._physics_scene_path = None # prepare cloner for environment replication - self.env_prim_paths = [f"{self.env_ns}/env_{i}" for i in range(self.cfg.num_envs)] - is_newton_replicated_scene = self.cfg.replicate_physics and self.physics_backend.startswith("newton") - - self.cloner_cfg = cloner.CloneCfg( - clone_regex=self.env_regex_ns, - clone_in_fabric=self.cfg.clone_in_fabric, - device=self.device, - physics_clone_fn=physics_clone_fn, - clone_usd=not is_newton_replicated_scene or has_kit(), - ) + self.cloner_cfg = cloner.CloneCfg(device=self.device) + env_root = self.cloner_cfg.clone_regex.rsplit("/", 1)[0] + self.env_prim_paths = [f"{env_root}/env_{i}" for i in range(self.cfg.num_envs)] # create source prim self.stage.DefinePrim(self.env_prim_paths[0], "Xform") - self.env_fmt = self.env_regex_ns.replace(".*", "{}") # allocate env indices self._ALL_INDICES = torch.arange(self.cfg.num_envs, dtype=torch.long, device=self.device) - pos, quat = cloner.grid_transforms(self.num_envs, self.cfg.env_spacing, device=self.device) - self._default_env_pose = torch.cat([pos, quat], dim=-1) - - homo_mask = torch.ones((1, self.num_envs), device=self.device, dtype=torch.bool) - # Suspend Fabric's USD notice listener enable fast usd cloning + # clone env_0 xform to env_1..env_{N-1} at grid origins + env_origins, _ = cloner.grid_transforms(self.num_envs, self.cfg.env_spacing, device=self.device) with cloner.disabled_fabric_change_notifies(self.stage, restore=False): - # copy empty prim of env_0 to env_1, env_2, ..., env_{num_envs-1} with correct location. - rep_args = (self.stage, [self.env_fmt.format(0)], [self.env_fmt], self._ALL_INDICES, homo_mask, pos, quat) - cloner.usd_replicate(*rep_args) + cloner.usd_replicate( + self.stage, + ["/World/envs/env_0"], + ["/World/envs/env_{}"], + self._ALL_INDICES, + positions=env_origins, + ) + # Always enter so a ClonePlan is published even when the scene cfg has no entities. self._global_prim_paths = list() - has_scene_cfg_entities = self._is_scene_setup_from_cfg() - if has_scene_cfg_entities: - self._clone_plan = self._build_clone_plan_from_cfg() - self.sim.set_clone_plan(self._clone_plan) - self._add_entities_from_cfg() - else: - self._clone_plan = cloner.ClonePlan( - sources=(self.env_fmt.format(0),), - destinations=(self.env_fmt,), - clone_mask=homo_mask, - ) - self.sim.set_clone_plan(self._clone_plan) + with cloner.ReplicateSession( + self._collect_asset_cfgs(), + num_clones=self.num_envs, + env_spacing=self.cfg.env_spacing, + device=self.device, + stage=self.stage, + clone_strategy=self.cloner_cfg.clone_strategy, + ): + if self._is_scene_setup_from_cfg(): + self._add_entities_from_cfg() - # Aggregate scene-data requirements from declared visualizers and constructed sensors, - # then publish to ``SimulationContext`` so downstream providers (constructed later by - # :meth:`SimulationContext.initialize_visualizers`) see the full picture in one read. self._aggregate_scene_data_requirements(requested_viz_types) - if has_scene_cfg_entities: - self.clone_environments(copy_from_source=(not self.cfg.replicate_physics)) - # Collision filtering is PhysX-specific (PhysxSchema.PhysxSceneAPI) - # Intentionally matches both physx and ovphysx (both are PhysX-based) - if self.cfg.filter_collisions and "physx" in self.physics_backend: - self.filter_collisions(self._global_prim_paths) + # Collision filtering is PhysX-only (matches both physx and ovphysx). + if self.cfg.filter_collisions and "physx" in self.physics_backend and self._is_scene_setup_from_cfg(): + self.filter_collisions(self._global_prim_paths) - def _build_clone_plan_from_cfg(self) -> cloner.ClonePlan | None: - """Build a clone plan from scene cfg spawn variants and write planned spawn paths. + def _collect_asset_cfgs(self) -> list[Any]: + """Flatten user-declared cfgs for :func:`~isaaclab.cloner.make_clone_plan`. - Returns ``None`` when the cfg has no env-scoped spawned assets. + Expands :class:`~isaaclab.assets.RigidObjectCollectionCfg` into its members, + resolves ``{ENV_REGEX_NS}`` macros, and orders sensors after non-sensors. """ - - def num_variants(spawn_cfg) -> int: - if isinstance(spawn_cfg, sim_utils.MultiAssetSpawnerCfg): - return len(spawn_cfg.assets_cfg) - if isinstance(spawn_cfg, sim_utils.MultiUsdFileCfg): - return 1 if isinstance(spawn_cfg.usd_path, str) else len(spawn_cfg.usd_path) - return 1 - - def set_spawn_paths(spawn_cfg, paths: list[str | None]) -> None: - if isinstance(spawn_cfg, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg)): - spawn_cfg.spawn_paths = paths - else: - active = [path for path in paths if path is not None] - if len(active) != 1: - raise ValueError("Single spawner expects exactly one planned source path.") - spawn_cfg.spawn_path = active[0] - cfg_fields = InteractiveSceneCfg.__dataclass_fields__ items = [(k, v) for k, v in self.cfg.__dict__.items() if k not in cfg_fields and v is not None] - ordered_items = [item for item in items if not isinstance(item[1], SensorBaseCfg)] - ordered_items += [item for item in items if isinstance(item[1], SensorBaseCfg)] - - # One group is one cfg's prim path template plus its spawn variants. - groups = [] - for _, asset_cfg in ordered_items: - cfgs = asset_cfg.rigid_objects.values() if isinstance(asset_cfg, RigidObjectCollectionCfg) else [asset_cfg] - for cfg in (cfg for cfg in cfgs if hasattr(cfg, "prim_path")): - prim_path = cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) - if not hasattr(cfg, "spawn") or cfg.spawn is None or self.env_ns not in prim_path: - continue - if (count := num_variants(cfg.spawn)) > 0: - groups.append((cfg, cfg.spawn, prim_path.replace(self.env_regex_ns, self.env_fmt), count)) - - if not groups: - return None - - # Homogeneous scenes still spawn sources at env_0, but publish the simpler env-root plan. - if all(count == 1 for _, _, _, count in groups): - for _, spawn_cfg, destination, _ in groups: - set_spawn_paths(spawn_cfg, [destination.format(0)]) - clone_mask = torch.ones((1, self.num_envs), device=self.device, dtype=torch.bool) - return cloner.ClonePlan( - sources=(self.env_fmt.format(0),), - destinations=(self.env_fmt,), - clone_mask=clone_mask, - ) - - sources, destinations, clone_mask = cloner.make_clone_plan( - sources=[[destination.format(i) for i in range(count)] for _, _, destination, count in groups], - destinations=[destination for _, _, destination, _ in groups], - num_clones=self.num_envs, - clone_strategy=self.cloner_cfg.clone_strategy, - device=self.device, - ) - - # Move each planned source entry to the first environment that actually uses it. - source_start = 0 - sources = list(sources) - for cfg, spawn_cfg, destination, count in groups: - submask = clone_mask[source_start : source_start + count] - env_ids = submask.to(torch.int).argmax(dim=1).tolist() - active = submask.any(dim=1).tolist() - paths = [destination.format(eid) if a else None for eid, a in zip(env_ids, active)] - for offset, path in enumerate(paths): - if path is not None: - sources[source_start + offset] = path - set_spawn_paths(spawn_cfg, paths) - source_start += count - - logger.debug("Built heterogeneous ClonePlan with %d source entries.", len(sources)) - return cloner.ClonePlan(sources=tuple(sources), destinations=destinations, clone_mask=clone_mask) - - def clone_environments(self, copy_from_source: bool = False): - """Creates clones of the environment ``/World/envs/env_0``. - - Args: - copy_from_source: (bool): If set to False, clones inherit from /World/envs/env_0 and mirror its changes. - If True, clones are independent copies of the source prim and won't reflect its changes (start-up time - may increase). Defaults to False. - """ - plan = self._clone_plan - assert self.sim is not None - if plan is None: - self.sim.set_clone_plan(None) - return - - # PhysX-only: set env id bit count for replicated physics. Newton handles env separation in its own API. - # Intentionally matches both physx and ovphysx (both are PhysX-based) - if self.cfg.replicate_physics and "physx" in self.physics_backend: - from pxr import Sdf # noqa: PLC0415 - - prim = self.stage.GetPrimAtPath("/physicsScene") - prim.CreateAttribute("physxScene:envIdInBoundsBitCount", Sdf.ValueTypeNames.Int).Set(4) - - # Suspend Fabric's USD notice listener around bulk authoring. ``restore=False`` because the downstream - # ``SimulationContext.reset`` does the Fabric resync — re-enabling here would batch-resync everything - # we just authored, which is slower than the unsuppressed baseline. - with cloner.disabled_fabric_change_notifies(self.stage, restore=False): - replicate_args = (plan.sources, plan.destinations, self._ALL_INDICES, plan.clone_mask) - - if not copy_from_source and self.cloner_cfg.physics_clone_fn is not None: - self.cloner_cfg.physics_clone_fn( - self.stage, - *replicate_args, - positions=self._default_env_pose[:, :3], - device=self.cloner_cfg.device, - ) - if self.cloner_cfg.clone_usd: - is_env_root_plan = len(plan.sources) == 1 and plan.destinations == (self.env_fmt,) - usd_positions = self._default_env_pose[:, :3] if is_env_root_plan else None - cloner.usd_replicate(self.stage, *replicate_args, positions=usd_positions) + ordered_items = [v for _, v in items if not isinstance(v, SensorBaseCfg)] + ordered_items += [v for _, v in items if isinstance(v, SensorBaseCfg)] - # Publish to ``SimulationContext`` (the canonical owner). The :attr:`clone_plan` - # property below forwards reads back through ``sim.get_clone_plan()`` so consumers - # holding a scene reference still see the published plan without a duplicate cache. - self.sim.set_clone_plan(plan) + cfgs: list[Any] = [] + for asset_cfg in ordered_items: + children = ( + asset_cfg.rigid_objects.values() if isinstance(asset_cfg, RigidObjectCollectionCfg) else [asset_cfg] + ) + for child in children: + if hasattr(child, "prim_path"): + child.prim_path = child.prim_path.format(ENV_REGEX_NS=self.cloner_cfg.clone_regex) + cfgs.append(child) + return cfgs def _aggregate_scene_data_requirements(self, visualizer_types=()) -> None: """Aggregate scene-data requirements from visualizers and sensor renderers. @@ -478,20 +357,6 @@ def device(self) -> str: """The device on which the scene is created.""" return sim_utils.SimulationContext.instance().device # pyright: ignore [reportOptionalMemberAccess] - @property - def env_ns(self) -> str: - """The namespace ``/World/envs`` in which all environments created. - - The environments are present w.r.t. this namespace under "env_{N}" prim, - where N is a natural number. - """ - return "/World/envs" - - @property - def env_regex_ns(self) -> str: - """The namespace ``/World/envs/env_.*`` in which all environments created.""" - return f"{self.env_ns}/env_.*" - @property def num_envs(self) -> int: """The number of environments handled by the scene.""" @@ -499,11 +364,12 @@ def num_envs(self) -> int: @property def env_origins(self) -> torch.Tensor: - """The origins of the environments in the scene. Shape is (num_envs, 3).""" + """Per-env world origins, shape ``(num_envs, 3)``. From the terrain when registered, + else from the published :class:`~isaaclab.cloner.ClonePlan`. + """ if self._terrain is not None: return self._terrain.env_origins - else: - return self._default_env_pose[:, :3] + return self.sim.get_clone_plan().positions @property def terrain(self) -> TerrainImporter | None: @@ -547,11 +413,11 @@ def surface_grippers(self) -> dict[str, SurfaceGripper]: @property def clone_plan(self) -> cloner.ClonePlan | None: - """Clone plan produced by :meth:`clone_environments`. + """Clone plan produced by the most recent replication. Forwards to :meth:`SimulationContext.get_clone_plan`, which is the canonical owner. The plan records the source paths, destination templates, and the per-env source - assignment mask. ``None`` until :meth:`clone_environments` runs. + assignment mask. ``None`` until :func:`isaaclab.cloner.replicate` has run. """ return self.sim.get_clone_plan() @@ -877,6 +743,9 @@ def _add_entities_from_cfg(self): # noqa: C901 # store paths that are in global collision filter self._global_prim_paths = list() + # Resolve the env-namespace convention from the cloner cfg once for this pass. + env_regex_ns = self.cloner_cfg.clone_regex + env_root = env_regex_ns.rsplit("/", 1)[0] # Process non-sensor entities before sensors so that asset prims exist in the template # when sensors (e.g. cameras attached to robot links) need to spawn under them. all_items = [ @@ -891,13 +760,13 @@ def _add_entities_from_cfg(self): # noqa: C901 for asset_name, asset_cfg in ordered_items: # resolve prim_path with env regex if hasattr(asset_cfg, "prim_path"): - asset_cfg.prim_path = asset_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) + asset_cfg.prim_path = asset_cfg.prim_path.format(ENV_REGEX_NS=env_regex_ns) # set spawn_path on spawner if cloning is needed if hasattr(asset_cfg, "spawn") and asset_cfg.spawn is not None: is_multi_spawner = isinstance( asset_cfg.spawn, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg) ) - if self.env_ns not in asset_cfg.prim_path: + if env_root not in asset_cfg.prim_path: asset_cfg.spawn.spawn_path = asset_cfg.prim_path elif is_multi_spawner and not asset_cfg.spawn.spawn_paths: raise RuntimeError(f"Clone planning did not assign spawn_paths for '{asset_cfg.prim_path}'.") @@ -917,13 +786,13 @@ def _add_entities_from_cfg(self): # noqa: C901 self._rigid_objects[asset_name] = asset_cfg.class_type(asset_cfg) elif isinstance(asset_cfg, RigidObjectCollectionCfg): for rigid_object_cfg in asset_cfg.rigid_objects.values(): - rigid_object_cfg.prim_path = rigid_object_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) + rigid_object_cfg.prim_path = rigid_object_cfg.prim_path.format(ENV_REGEX_NS=env_regex_ns) # set spawn_path on spawner if cloning is needed if hasattr(rigid_object_cfg, "spawn") and rigid_object_cfg.spawn is not None: is_multi_spawner = isinstance( rigid_object_cfg.spawn, (sim_utils.MultiAssetSpawnerCfg, sim_utils.MultiUsdFileCfg) ) - if self.env_ns not in rigid_object_cfg.prim_path: + if env_root not in rigid_object_cfg.prim_path: rigid_object_cfg.spawn.spawn_path = rigid_object_cfg.prim_path elif is_multi_spawner and not rigid_object_cfg.spawn.spawn_paths: raise RuntimeError( @@ -946,32 +815,32 @@ def _add_entities_from_cfg(self): # noqa: C901 if isinstance(asset_cfg, FrameTransformerCfg): updated_target_frames = [] for target_frame in asset_cfg.target_frames: - target_frame.prim_path = target_frame.prim_path.format(ENV_REGEX_NS=self.env_regex_ns) + target_frame.prim_path = target_frame.prim_path.format(ENV_REGEX_NS=env_regex_ns) updated_target_frames.append(target_frame) asset_cfg.target_frames = updated_target_frames elif isinstance(asset_cfg, ContactSensorCfg): asset_cfg.filter_prim_paths_expr = [ - p.format(ENV_REGEX_NS=self.env_regex_ns) for p in asset_cfg.filter_prim_paths_expr + p.format(ENV_REGEX_NS=env_regex_ns) for p in asset_cfg.filter_prim_paths_expr ] if hasattr(asset_cfg, "sensor_shape_prim_expr") and asset_cfg.sensor_shape_prim_expr: asset_cfg.sensor_shape_prim_expr = [ - p.format(ENV_REGEX_NS=self.env_regex_ns) for p in asset_cfg.sensor_shape_prim_expr + p.format(ENV_REGEX_NS=env_regex_ns) for p in asset_cfg.sensor_shape_prim_expr ] if hasattr(asset_cfg, "filter_shape_prim_expr") and asset_cfg.filter_shape_prim_expr: asset_cfg.filter_shape_prim_expr = [ - p.format(ENV_REGEX_NS=self.env_regex_ns) for p in asset_cfg.filter_shape_prim_expr + p.format(ENV_REGEX_NS=env_regex_ns) for p in asset_cfg.filter_shape_prim_expr ] elif isinstance(asset_cfg, VisuoTactileSensorCfg): if hasattr(asset_cfg, "camera_cfg") and asset_cfg.camera_cfg is not None: asset_cfg.camera_cfg.prim_path = asset_cfg.camera_cfg.prim_path.format( - ENV_REGEX_NS=self.env_regex_ns + ENV_REGEX_NS=env_regex_ns ) if ( hasattr(asset_cfg, "contact_object_prim_path_expr") and asset_cfg.contact_object_prim_path_expr is not None ): asset_cfg.contact_object_prim_path_expr = asset_cfg.contact_object_prim_path_expr.format( - ENV_REGEX_NS=self.env_regex_ns + ENV_REGEX_NS=env_regex_ns ) self._sensors[asset_name] = asset_cfg.class_type(asset_cfg) diff --git a/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py b/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py index be5fa82fd7d0..8ff2f584ed53 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene_cfg.py @@ -124,15 +124,8 @@ class MySceneCfg(InteractiveSceneCfg): """ clone_in_fabric: bool = False - """Enable/disable cloning in fabric. Default is False. - - Omniverse Fabric is a more optimized method for performing cloning in scene creation. This reduces the time - taken to create the scene. However, it limits flexibility in accessing the stage through USD APIs and instead, - the stage must be accessed through USDRT. - - .. note:: - Cloning in fabric can only be enabled if :attr:`replicated_physics` is also enabled. - If :attr:`replicated_physics` is ``False``, cloning in Fabric will automatically - default to ``False``. + """Deprecated legacy Fabric cloning flag. Default is False. + Queued replication no longer forwards this flag to the PhysX replicator; + ``useFabricForReplication`` is always ``False``. """ diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index d7fd74d04a6c..5ed97a3825f5 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -17,6 +17,7 @@ import isaaclab.sim as sim_utils import isaaclab.utils.sensors as sensor_utils +from isaaclab.cloner import queue_usd_replication from isaaclab.renderers import BaseRenderer, CameraRenderSpec from isaaclab.sim.views import FrameView from isaaclab.utils import to_camel_case @@ -171,6 +172,7 @@ def __init__(self, cfg: CameraCfg): spawn.func(spawn_target, spawn, translation=self.cfg.offset.pos, orientation=rot_offset) if not sim_utils.find_matching_prims(spawn_target): raise RuntimeError(f"Could not find prim with path {spawn_target!r}.") + queue_usd_replication(self._source_cfg) # An ISP (any ``isp_cfg`` other than ``None``) requires the HDR AOV; # an explicit ``"rgb_hdr"`` in ``data_types`` also requires the diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/base_ray_caster.py b/source/isaaclab/isaaclab/sensors/ray_caster/base_ray_caster.py index b9b6aa8b7bc6..5a9534061120 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/base_ray_caster.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/base_ray_caster.py @@ -17,6 +17,7 @@ import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils +from isaaclab.cloner import queue_usd_replication from isaaclab.markers import VisualizationMarkers from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.utils.warp import ProxyArray, convert_to_warp_mesh @@ -69,6 +70,7 @@ def __init__(self, cfg: RayCasterCfg): """ BaseRayCaster._instance_count += 1 super().__init__(cfg) + queue_usd_replication(self._source_cfg) self._data = RayCasterData() def __str__(self) -> str: diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index 86a5f8561d96..a72ed6b9efaa 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -60,6 +60,7 @@ def __init__(self, cfg: SensorBaseCfg): # check that the config is valid cfg.validate() # store inputs + self._source_cfg = cfg self.cfg = cfg.copy() # flag for whether the sensor is initialized self._is_initialized = False @@ -225,7 +226,8 @@ def _initialize_impl(self): self._device = sim.device self._backend = sim.backend self._sim_physics_dt = sim.get_physics_dt() - # Count number of environments. + # Count number of environments. Prefer the active simulation's clone plan when USD + # only carries the env_0 prototype (e.g. Newton clones solver-side). self._clone_plan = sim.get_clone_plan() clone_plan = self._clone_plan clone_plan_matches = () @@ -234,6 +236,10 @@ def _initialize_impl(self): if clone_plan_matches: self._parent_prims = [] self._num_envs = int(clone_plan.clone_mask.shape[1]) + elif clone_plan is not None: + env_prim_path_expr = self.cfg.prim_path.rsplit("/", 1)[0] + self._parent_prims = sim_utils.find_matching_prims(env_prim_path_expr) + self._num_envs = int(clone_plan.env_ids.numel()) else: env_prim_path_expr = self.cfg.prim_path.rsplit("/", 1)[0] self._parent_prims = sim_utils.find_matching_prims(env_prim_path_expr) diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 8b1400b6d8ed..334272636871 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -183,7 +183,7 @@ def __init__(self, cfg: SimulationCfg | None = None): self._scene_data_requirements = SceneDataRequirement() # Clone plan published by InteractiveScene after cloning. Providers (e.g. the # Newton visualizer model rebuilder on a PhysX backend) consume this to derive - # their own backend args. None until :meth:`InteractiveScene.clone_environments` runs. + # their own backend args. None until a replication session publishes a plan. self._clone_plan: ClonePlan | None = None # Default visualization dt used before/without visualizer initialization. physics_dt = getattr(self.cfg.physics, "dt", None) @@ -682,9 +682,9 @@ def update_scene_data_requirements(self, requirements: SceneDataRequirement) -> def get_clone_plan(self) -> ClonePlan | None: """Return the clone plan published by the scene. - Set by :meth:`InteractiveScene.clone_environments` after replication. Consumed by - scene data providers that build backend models (e.g. Newton visualizer model on a - PhysX backend) from the same plan the cloner used. ``None`` until the scene clones. + Set after replication. Consumed by scene data providers that build backend models + (e.g. Newton visualizer model on a PhysX backend) from the same plan the cloner used. + ``None`` until the scene replicates. """ return self._clone_plan diff --git a/source/isaaclab/test/scene/test_interactive_scene.py b/source/isaaclab/test/scene/test_interactive_scene.py index ce8b2a6cb26d..a2ddc05f5eae 100644 --- a/source/isaaclab/test/scene/test_interactive_scene.py +++ b/source/isaaclab/test/scene/test_interactive_scene.py @@ -12,7 +12,6 @@ """Rest everything follows.""" -import contextlib from types import SimpleNamespace import pytest @@ -21,6 +20,7 @@ import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg, RigidObjectCfg, RigidObjectCollectionCfg +from isaaclab.cloner import CloneCfg from isaaclab.physics.scene_data_requirements import SceneDataRequirement from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sim import build_simulation_context @@ -130,255 +130,36 @@ def test_reset_to_env_ids_input_types(device, setup_scene): assert_state_equal(prev_state, scene.get_state()) -def test_clone_environments_executes_env_root_plan_with_positions(monkeypatch: pytest.MonkeyPatch): - """Env-root plans replicate the whole environment and keep grid positions.""" - from isaaclab.cloner import ClonePlan +def test_scene_publishes_plan_via_replicate(monkeypatch: pytest.MonkeyPatch): + """A cfg-driven scene forwards the right plan and stage to cloner.replicate. - scene = object.__new__(InteractiveScene) - scene.cfg = SimpleNamespace(replicate_physics=False, num_envs=3) - scene.stage = object() - scene.physics_backend = "physx" - scene._sensors = {} - - set_plan_calls: list = [] - sim_state: dict = {"plan": None} - - def _set_clone_plan(plan): - sim_state["plan"] = plan - set_plan_calls.append(plan) - - scene.sim = SimpleNamespace( - get_scene_data_requirements=lambda: SceneDataRequirement(), - update_scene_data_requirements=lambda requirements: None, - set_clone_plan=_set_clone_plan, - get_clone_plan=lambda: sim_state["plan"], - ) - scene.env_fmt = "/World/envs/env_{}" - scene._ALL_INDICES = torch.arange(3, dtype=torch.long) - scene._default_env_pose = torch.zeros((3, 7), dtype=torch.float32) - scene._default_env_pose[:, 6] = 1.0 # identity quaternion (xyzw) - scene._clone_plan = ClonePlan( - sources=(scene.env_fmt.format(0),), - destinations=(scene.env_fmt,), - clone_mask=torch.ones((1, scene.num_envs), dtype=torch.bool), - ) - # Avoid binding this unit test to global SimulationContext singleton state. - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) - - # ``disabled_fabric_change_notifies`` resolves the stage via UsdUtils.StageCache and would - # crash on the bare ``object()`` mocked above. This unit test exercises clone-dispatch - # logic only; the fabric notice path has its own coverage in ``test_cloner.py``. - @contextlib.contextmanager - def _noop_fabric_notices(stage, *, restore=True): - yield - - monkeypatch.setattr("isaaclab.scene.interactive_scene.cloner.disabled_fabric_change_notifies", _noop_fabric_notices) - - physics_calls = [] - usd_calls = [] - - def _physics_clone_fn(stage, *args, **kwargs): - physics_calls.append((stage, args, kwargs)) - - def _usd_replicate(stage, *args, **kwargs): - usd_calls.append((stage, args, kwargs)) - - scene.cloner_cfg = SimpleNamespace( - device="cpu", - physics_clone_fn=_physics_clone_fn, - clone_usd=True, - ) - monkeypatch.setattr("isaaclab.scene.interactive_scene.cloner.usd_replicate", _usd_replicate) - - scene.clone_environments(copy_from_source=False) - assert len(physics_calls) == 1 - assert len(usd_calls) == 1 - mapping = physics_calls[0][1][3] - assert mapping.dtype == torch.bool - assert mapping.shape == (1, scene.num_envs) - # Positions are a zero-copy ``[:, :3]`` view of ``_default_env_pose``: same storage, sliced shape. - pose_storage_ptr = scene._default_env_pose.untyped_storage().data_ptr() - physics_positions = physics_calls[0][2]["positions"] - usd_positions = usd_calls[0][2]["positions"] - assert physics_positions.untyped_storage().data_ptr() == pose_storage_ptr - assert physics_positions.shape == (scene.num_envs, 3) - assert usd_positions.untyped_storage().data_ptr() == pose_storage_ptr - assert usd_positions.shape == (scene.num_envs, 3) - assert len(set_plan_calls) == 1 - plan = set_plan_calls[-1] - assert isinstance(plan, ClonePlan) - assert plan.sources == (scene.env_fmt.format(0),) - assert plan.destinations == (scene.env_fmt,) - assert plan.clone_mask.shape == (1, scene.num_envs) - assert scene.clone_plan is plan - - physics_calls.clear() - usd_calls.clear() - set_plan_calls.clear() - scene.clone_environments(copy_from_source=True) - assert len(physics_calls) == 0 - assert len(usd_calls) == 1 - assert len(set_plan_calls) == 1 - - -def test_clone_environments_skips_replication_without_plan(): - """Direct-path cfg scenes publish no plan and do not dispatch cloners.""" - scene = object.__new__(InteractiveScene) - scene._clone_plan = None - set_plan_calls = [] - scene.sim = SimpleNamespace(set_clone_plan=set_plan_calls.append) - - scene.clone_environments(copy_from_source=False) - - assert set_plan_calls == [None] - - -def test_clone_environments_executes_asset_level_plan_without_usd_positions(monkeypatch: pytest.MonkeyPatch): - """Asset-level plans preserve env-root transforms by skipping USD positions.""" - from isaaclab.cloner import ClonePlan - - scene = object.__new__(InteractiveScene) - scene.cfg = SimpleNamespace(replicate_physics=False, num_envs=2) - scene.stage = object() - scene.physics_backend = "physx" - scene._sensors = {} - scene.env_fmt = "/World/envs/env_{}" - scene._ALL_INDICES = torch.arange(2, dtype=torch.long) - scene._default_env_pose = torch.ones((2, 7), dtype=torch.float32) - scene._default_env_pose[:, 3:6] = 0.0 # identity quaternion (xyzw) - scene._clone_plan = ClonePlan( - sources=("/World/envs/env_0/Object", "/World/envs/env_1/Object"), - destinations=("/World/envs/env_{}/Object", "/World/envs/env_{}/Object"), - clone_mask=torch.tensor([[True, False], [False, True]], dtype=torch.bool), - ) - - set_plan_calls: list = [] - scene.sim = SimpleNamespace(set_clone_plan=set_plan_calls.append) - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) - - @contextlib.contextmanager - def _noop_fabric_notices(stage, *, restore=True): - yield - - monkeypatch.setattr("isaaclab.scene.interactive_scene.cloner.disabled_fabric_change_notifies", _noop_fabric_notices) - monkeypatch.setattr( - "isaaclab.scene.interactive_scene.cloner.usd_replicate", - lambda *args, **kwargs: usd_calls.append((args, kwargs)), - ) - - physics_calls = [] - usd_calls = [] - scene.cloner_cfg = SimpleNamespace( - device="cpu", - physics_clone_fn=lambda *args, **kwargs: physics_calls.append((args, kwargs)), - clone_usd=True, - ) - - scene.clone_environments(copy_from_source=False) - - assert len(physics_calls) == 1 - physics_positions = physics_calls[0][1]["positions"] - assert physics_positions.untyped_storage().data_ptr() == scene._default_env_pose.untyped_storage().data_ptr() - assert physics_positions.shape == (scene.num_envs, 3) - assert len(usd_calls) == 1 - assert usd_calls[0][1]["positions"] is None - assert set_plan_calls == [scene._clone_plan] - - -def test_build_clone_plan_from_cfg_plans_multi_and_single_spawners(monkeypatch: pytest.MonkeyPatch): - """Heterogeneous planning writes source paths for multi and single spawners.""" - from isaaclab.cloner import sequential - - scene = object.__new__(InteractiveScene) - scene.cfg = SimpleNamespace( - num_envs=4, - object=SimpleNamespace( - prim_path="{ENV_REGEX_NS}/Object", - spawn=sim_utils.MultiAssetSpawnerCfg( - assets_cfg=[ - sim_utils.ConeCfg(radius=0.1, height=0.2), - sim_utils.SphereCfg(radius=0.1), - ] - ), - ), - robot=SimpleNamespace( - prim_path="{ENV_REGEX_NS}/Robot", - spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), - ), - ) - scene.env_fmt = "/World/envs/env_{}" - scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) - - plan = scene._build_clone_plan_from_cfg() - - assert plan is not None - assert plan.sources == ( - "/World/envs/env_0/Object", - "/World/envs/env_1/Object", - "/World/envs/env_0/Robot", - ) - assert plan.destinations == ( - "/World/envs/env_{}/Object", - "/World/envs/env_{}/Object", - "/World/envs/env_{}/Robot", - ) - assert scene.cfg.object.spawn.spawn_paths == ["/World/envs/env_0/Object", "/World/envs/env_1/Object"] - assert scene.cfg.robot.spawn.spawn_path == "/World/envs/env_0/Robot" - assert scene.cfg.object.prim_path == "{ENV_REGEX_NS}/Object" - assert scene.cfg.robot.prim_path == "{ENV_REGEX_NS}/Robot" - assert torch.equal(plan.clone_mask.to(torch.int).argmax(dim=0).cpu(), torch.tensor([0, 1, 0, 1])) + Uses a test-seam fake to isolate this unit test from real backend dispatch; queue + lifecycle is owned by :func:`replicate` itself (snapshot-and-clear) and does not + need any cleanup hook here. + """ + import isaaclab.cloner.replicate_session as replicate_session_module + captured: list = [] -def test_build_clone_plan_from_cfg_defaults_to_env0_plan(monkeypatch: pytest.MonkeyPatch): - """Homogeneous cfg scenes use the default env_0-to-all ClonePlan.""" - from isaaclab.cloner import sequential + def fake_replicate(plan, *, stage): + captured.append((plan, stage)) - scene = object.__new__(InteractiveScene) - scene.cfg = SimpleNamespace( - num_envs=3, - robot=SimpleNamespace( - prim_path="{ENV_REGEX_NS}/Robot", - spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), - ), - ) - scene.env_fmt = "/World/envs/env_{}" - scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + monkeypatch.setattr(replicate_session_module, "replicate", fake_replicate) - plan = scene._build_clone_plan_from_cfg() + with build_simulation_context(device="cpu", auto_add_lighting=False, add_ground_plane=False) as sim: + sim._app_control_on_stop_handle = None + scene = InteractiveScene(MySceneCfg(num_envs=4, env_spacing=1.0)) - assert plan is not None + assert len(captured) == 1 + plan, stage = captured[0] assert plan.sources == ("/World/envs/env_0",) - assert plan.destinations == (scene.env_fmt,) - assert plan.clone_mask.shape == (1, scene.num_envs) - assert scene.cfg.robot.spawn.spawn_path == "/World/envs/env_0/Robot" - + assert plan.destinations == ("/World/envs/env_{}",) + assert plan.clone_mask.shape == (1, 4) + assert stage is scene.stage -def test_build_clone_plan_from_cfg_returns_none_without_env_scoped_groups(monkeypatch: pytest.MonkeyPatch): - """Direct-path cfg scenes should not force env-root replication.""" - from isaaclab.cloner import sequential - - scene = object.__new__(InteractiveScene) - scene.cfg = SimpleNamespace( - num_envs=1, - robot=SimpleNamespace( - prim_path="/World/Robot", - spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), - ), - ) - scene.env_fmt = "/World/envs/env_{}" - scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) - - assert scene._build_clone_plan_from_cfg() is None - assert scene.cfg.robot.spawn.spawn_path is None - - -def test_build_clone_plan_from_cfg_sets_collection_member_paths(monkeypatch: pytest.MonkeyPatch): - """Rigid object collection members are planned independently.""" - from isaaclab.cloner import sequential +def test_collect_asset_cfgs_resolves_env_regex_macros(): + """_collect_asset_cfgs rewrites {ENV_REGEX_NS} macros and expands collections.""" scene = object.__new__(InteractiveScene) cube_cfg = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/Cube", @@ -391,51 +172,31 @@ def test_build_clone_plan_from_cfg_sets_collection_member_paths(monkeypatch: pyt ), ) scene.cfg = SimpleNamespace( - num_envs=4, + num_envs=2, objects=RigidObjectCollectionCfg(rigid_objects={"cube": cube_cfg, "shape": shape_cfg}), ) - scene.env_fmt = "/World/envs/env_{}" - scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + scene.cloner_cfg = CloneCfg() - plan = scene._build_clone_plan_from_cfg() + cfgs = scene._collect_asset_cfgs() - assert plan is not None - planned_cube = scene.cfg.objects.rigid_objects["cube"] - planned_shape = scene.cfg.objects.rigid_objects["shape"] - assert planned_cube.spawn.spawn_path == "/World/envs/env_0/Cube" - assert planned_shape.spawn.spawn_paths == ["/World/envs/env_0/Shape", "/World/envs/env_1/Shape"] - assert "/World/envs/env_{}/Cube" in plan.destinations - assert "/World/envs/env_{}/Shape" in plan.destinations + prim_paths = sorted(c.prim_path for c in cfgs) + assert prim_paths == ["/World/envs/env_.*/Cube", "/World/envs/env_.*/Shape"] -def test_build_clone_plan_from_cfg_marks_unused_variants(monkeypatch: pytest.MonkeyPatch): - """Unused variants keep a mask row but do not get spawned.""" - from isaaclab.cloner import sequential +def test_collect_asset_cfgs_orders_sensors_last(): + """Non-sensor cfgs precede sensor cfgs in _collect_asset_cfgs output.""" + from isaaclab.sensors import ContactSensorCfg scene = object.__new__(InteractiveScene) - scene.cfg = SimpleNamespace( - num_envs=2, - object=SimpleNamespace( - prim_path="{ENV_REGEX_NS}/Object", - spawn=sim_utils.MultiAssetSpawnerCfg( - assets_cfg=[ - sim_utils.ConeCfg(radius=0.1, height=0.2), - sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), - sim_utils.SphereCfg(radius=0.1), - ] - ), - ), - ) - scene.env_fmt = "/World/envs/env_{}" - scene.cloner_cfg = SimpleNamespace(clone_strategy=sequential) - monkeypatch.setattr(InteractiveScene, "device", property(lambda self: "cpu")) + sensor = ContactSensorCfg(prim_path="{ENV_REGEX_NS}/Robot") + body = SimpleNamespace(prim_path="{ENV_REGEX_NS}/Robot") + scene.cfg = SimpleNamespace(num_envs=1, sensor=sensor, body=body) + scene.cloner_cfg = CloneCfg() - plan = scene._build_clone_plan_from_cfg() + cfgs = scene._collect_asset_cfgs() - assert plan is not None - assert scene.cfg.object.spawn.spawn_paths == ["/World/envs/env_0/Object", "/World/envs/env_1/Object", None] - assert plan.clone_mask[2].sum() == 0 + # Sensors come after non-sensor entities so they can bind to spawned bodies. + assert cfgs.index(body) < cfgs.index(sensor) def test_aggregate_scene_data_requirements_merges_visualizers_and_renderers(monkeypatch: pytest.MonkeyPatch): diff --git a/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py b/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py index 2e6c9f471b04..befaa63d9a6b 100644 --- a/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py +++ b/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py @@ -28,6 +28,7 @@ from pxr import Gf, Sdf, Usd, UsdGeom +import isaaclab.cloner as cloner import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg @@ -556,6 +557,14 @@ def render_synthetic_gaussian_scene( renderer_cfg=renderer_cfg, ) camera = Camera(cfg) + # Camera is constructed after the scene's ReplicateSession has exited, so its + # queued USD replication needs an explicit drain (Path B). Reuse the scene's + # env positions so env_origins stays consistent. + published = sim.get_clone_plan() + positions = published.positions if published is not None else None + src, dst = "/World/envs/env_0", "/World/envs/env_{}" + camera_plan = cloner.ClonePlan.from_env_0(src, dst, num_envs, str(sim.device), positions) + cloner.replicate(camera_plan, stage=sim.stage) sim.reset() for _ in range(stabilisation_steps): sim.step() diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 99a44bc6958a..360eb8f4d9ef 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -515,6 +515,9 @@ def _create_heterogeneous_clone_scene(sim: sim_utils.SimulationContext, num_envs env_fmt + "/Object", ), clone_mask=torch.cat([robot_mask, object_mask], dim=0), + env_ids=env_ids, + positions=None, + cfg_rows={}, ) ) sim_utils.update_stage() diff --git a/source/isaaclab/test/sensors/test_ray_caster_integration.py b/source/isaaclab/test/sensors/test_ray_caster_integration.py index d197bf5f558f..2043d6e34d2e 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_integration.py +++ b/source/isaaclab/test/sensors/test_ray_caster_integration.py @@ -358,6 +358,9 @@ def _create_object_body(path: str) -> None: sources=("/World/envs/env_0/Object", "/World/envs/env_1/Object"), destinations=("/World/envs/env_{}/Object", "/World/envs/env_{}/Object"), clone_mask=torch.tensor([[True, False, True], [False, True, False]], dtype=torch.bool, device=sim.device), + env_ids=torch.arange(3, dtype=torch.long, device=sim.device), + positions=None, + cfg_rows={}, ) ) sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_cloner.py b/source/isaaclab/test/sim/test_cloner.py index c89eadfc232e..14e30f4970b9 100644 --- a/source/isaaclab/test/sim/test_cloner.py +++ b/source/isaaclab/test/sim/test_cloner.py @@ -14,14 +14,28 @@ """Rest everything follows.""" +from types import SimpleNamespace +from unittest.mock import MagicMock + import pytest import torch from pxr import UsdGeom import isaaclab.sim as sim_utils -from isaaclab.cloner import ClonePlan, make_clone_plan, sequential, usd_replicate -from isaaclab.cloner.cloner_utils import iter_clone_plan_matches, resolve_clone_plan_source +from isaaclab.cloner import ( + REPLICATION_QUEUE, + ClonePlan, + UsdReplicateContext, + grid_transforms, + iter_clone_plan_matches, + make_clone_plan, + queue_usd_replication, + replicate, + resolve_clone_plan_source, + sequential, + usd_replicate, +) from isaaclab.sim import build_simulation_context pytestmark = pytest.mark.isaacsim_ci @@ -34,6 +48,14 @@ def sim(request): yield sim +@pytest.fixture(autouse=True) +def _drain_replication_queue(): + """Ensure REPLICATION_QUEUE starts empty for every test and is cleared after.""" + REPLICATION_QUEUE.clear() + yield + REPLICATION_QUEUE.clear() + + def test_usd_replicate_with_positions_and_mask(sim): """Replicate sources to selected envs and author translate ops from positions.""" # Prepare sources under /World/template @@ -76,6 +98,28 @@ def test_usd_replicate_with_positions_and_mask(sim): assert any(op.GetOpType() == UsdGeom.XformOp.TypeTranslate for op in ops) +def test_usd_replicate_context_queue_and_replicate(sim): + """UsdReplicateContext queues copy specs and applies them on replicate.""" + sim_utils.create_prim("/World/template", "Xform") + sim_utils.create_prim("/World/template/A", "Xform") + sim_utils.create_prim("/World/envs", "Xform") + sim_utils.create_prim("/World/envs/env_0", "Xform") + sim_utils.create_prim("/World/envs/env_1", "Xform") + + stage = sim_utils.get_current_stage() + ctx = UsdReplicateContext(stage) + ctx.queue_mapping( + sources=["/World/template/A"], + destinations=["/World/envs/env_{}/A"], + env_ids=torch.tensor([0, 1], dtype=torch.long), + ) + assert not stage.GetPrimAtPath("/World/envs/env_1/A").IsValid() + ctx.replicate() + + assert stage.GetPrimAtPath("/World/envs/env_0/A").IsValid() + assert stage.GetPrimAtPath("/World/envs/env_1/A").IsValid() + + def test_usd_replicate_depth_order_parent_child(sim): """Replicate parent and child when provided out of order; parent should exist before child.""" # Prepare sources @@ -104,12 +148,7 @@ def test_usd_replicate_depth_order_parent_child(sim): def test_usd_replicate_self_copy_skips_copy_spec(sim): - """usd_replicate must not call Sdf.CopySpec when source and destination paths are identical. - - Sdf.CopySpec(src, src) is a no-op in the current USD version so it does not corrupt children, - but the call is still wasteful. The guard ensures it is skipped entirely. This test mocks - Sdf.CopySpec to verify it is called exactly once (for env_1) and never for the self case (env_0). - """ + """usd_replicate must not call Sdf.CopySpec when source and destination paths are identical.""" from unittest.mock import patch import isaaclab.cloner.cloner_utils as _cloner_mod @@ -137,7 +176,6 @@ def capturing_copy_spec(src_layer, src_path, dst_layer, dst_path): mask=torch.ones((1, 2), dtype=torch.bool), ) - # CopySpec must be called for env_1 but never for env_0 (self-copy) assert all(src != dst for src, dst in copy_calls), f"Self-copy detected in CopySpec calls: {copy_calls}" assert any(dst == "/World/envs/env_1" for _, dst in copy_calls), "CopySpec was not called for env_1" @@ -181,19 +219,7 @@ def capturing_copy_spec(src_layer, src_path, dst_layer, dst_path): def test_clone_decorator_wildcard_patterns( sim, parent_paths, spawn_pattern, expected_child_paths, bad_path, match_expr ): - """The @clone decorator handles two distinct wildcard patterns correctly. - - Case A – ``.*`` in root_path (parent is a regex): the child prim is spawned at - ``source_prim_paths[0]`` as a prototype and then copied to every other matching - parent via ``Sdf.CopySpec``, so **all** parents end up with the child. The old - ``prim_path.replace(".*", "0")`` approach created spurious intermediate prims - that inflated ``find_matching_prims`` counts and broke tiled-camera initialization. - - Case B – ``.*`` only in asset_path (leaf): no parent regex, so - ``source_prim_paths == [root_path]`` (one entry, no copy step). Replacing - ``".*"`` → ``"0"`` in the asset name gives the intended prototype name - (e.g. ``proto_asset_0``) under the single real parent. - """ + """The @clone decorator handles two distinct wildcard patterns correctly.""" for path in parent_paths: sim_utils.create_prim(path, "Xform") @@ -202,19 +228,16 @@ def test_clone_decorator_wildcard_patterns( stage = sim_utils.get_current_stage() - # Every expected child path must exist for child_path in expected_child_paths: assert stage.GetPrimAtPath(child_path).IsValid(), ( f"Prim was not spawned at '{child_path}'. The @clone decorator may have used the wrong spawn path." ) - # The spurious path from the old replace(".*", "0") must NOT exist assert not stage.GetPrimAtPath(bad_path).IsValid(), ( f"Spurious prim found at '{bad_path}'. " "The @clone decorator incorrectly derived the spawn path by replacing '.*' with '0'." ) - # find_matching_prims must see exactly the original parents — no spurious extras all_matching = sim_utils.find_matching_prims(match_expr) assert len(all_matching) == len(parent_paths), ( f"Expected {len(parent_paths)} matching prims, got {len(all_matching)}. " @@ -222,35 +245,354 @@ def test_clone_decorator_wildcard_patterns( ) -def test_make_clone_plan_returns_flat_source_rows(sim): - """make_clone_plan exposes the flat source-to-env mask used by scene cloning.""" - sources, destinations, clone_mask = make_clone_plan( - [["/World/envs/env_0/Object", "/World/envs/env_1/Object"]], - ["/World/envs/env_{}/Object"], +def test_queue_usd_replication_only_appends(sim): + """queue_usd_replication must only append to REPLICATION_QUEUE — no other side effects.""" + cfg_a = SimpleNamespace(prim_path="/World/envs/env_.*/Robot") + cfg_b = SimpleNamespace(prim_path="/World/envs/env_.*/Object") + + queue_usd_replication(cfg_a) + queue_usd_replication(cfg_b) + + assert [(cfg_a, UsdReplicateContext), (cfg_b, UsdReplicateContext)] == REPLICATION_QUEUE + + +def test_make_clone_plan_homogeneous_returns_env_root_plan(sim): + """Homogeneous (single-variant) cfgs produce one source row at the env root.""" + cube = SimpleNamespace( + prim_path="/World/envs/env_.*/Robot", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ) + + plan = make_clone_plan( + cfgs=[cube], num_clones=4, + env_spacing=1.0, + device=sim.cfg.device, + ) + + assert plan.sources == ("/World/envs/env_0",) + assert plan.destinations == ("/World/envs/env_{}",) + assert plan.clone_mask.shape == (1, 4) + assert plan.clone_mask.all() + assert plan.cfg_rows[id(cube)] == (0,) + assert plan.env_ids.shape == (4,) + assert plan.positions.shape == (4, 3) + assert cube.spawn.spawn_path == "/World/envs/env_0/Robot" + + +def test_make_clone_plan_heterogeneous_mutates_spawn_paths(sim): + """Multi-variant spawners get per-variant spawn_paths and contribute multiple plan rows.""" + multi_cfg = SimpleNamespace( + prim_path="/World/envs/env_.*/Object", + spawn=sim_utils.MultiAssetSpawnerCfg( + assets_cfg=[ + sim_utils.ConeCfg(radius=0.1, height=0.2), + sim_utils.SphereCfg(radius=0.1), + ] + ), + ) + plain_cfg = SimpleNamespace( + prim_path="/World/envs/env_.*/Robot", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ) + + plan = make_clone_plan( + cfgs=[multi_cfg, plain_cfg], + num_clones=4, + env_spacing=1.0, + device=sim.cfg.device, clone_strategy=sequential, + ) + + assert plan.destinations == ( + "/World/envs/env_{}/Object", + "/World/envs/env_{}/Object", + "/World/envs/env_{}/Robot", + ) + assert plan.cfg_rows[id(multi_cfg)] == (0, 1) + assert plan.cfg_rows[id(plain_cfg)] == (2,) + assert multi_cfg.spawn.spawn_paths == ["/World/envs/env_0/Object", "/World/envs/env_1/Object"] + assert plain_cfg.spawn.spawn_path == "/World/envs/env_0/Robot" + + +def test_make_clone_plan_skips_global_cfgs(sim): + """Cfgs whose prim_path is not under /World/envs/ are excluded from the plan.""" + global_cfg = SimpleNamespace( + prim_path="/World/global/Robot", + spawn=sim_utils.CuboidCfg(size=(0.1, 0.1, 0.1)), + ) + + plan = make_clone_plan( + cfgs=[global_cfg], + num_clones=3, + env_spacing=1.0, device=sim.cfg.device, ) - assert sources == ("/World/envs/env_0/Object", "/World/envs/env_1/Object") - assert destinations == ("/World/envs/env_{}/Object", "/World/envs/env_{}/Object") - assert clone_mask.shape == (2, 4) - assert clone_mask.dtype == torch.bool - assert torch.all(clone_mask.sum(dim=0) == 1) - actual_source_idx = clone_mask.to(torch.int).argmax(dim=0).cpu() - assert torch.equal(actual_source_idx, torch.tensor([0, 1, 0, 1])) + assert plan.sources == () + assert plan.destinations == () + assert plan.clone_mask.shape == (0, 3) + assert plan.cfg_rows == {} -def test_iter_clone_plan_matches(sim): - """ClonePlan entries can be matched by destination path expression.""" - sources, destinations, clone_mask = make_clone_plan( - [["/World/envs/env_0/Object", "/World/envs/env_1/Object"]], - ["/World/envs/env_{}/Object"], +def test_clone_plan_from_env_0_populates_cfg_rows(sim): + """from_env_0 auto-maps queued env-scoped cfgs to row 0 and excludes global ones.""" + env_cfg_a = SimpleNamespace(prim_path="/World/envs/env_.*/Robot") + env_cfg_b = SimpleNamespace(prim_path="/World/envs/env_.*/Object") + global_cfg = SimpleNamespace(prim_path="/World/global/Light") + + queue_usd_replication(env_cfg_a) + queue_usd_replication(env_cfg_b) + queue_usd_replication(global_cfg) + + plan = ClonePlan.from_env_0( + source="/World/envs/env_0", + destination="/World/envs/env_{}", num_clones=4, - clone_strategy=sequential, device=sim.cfg.device, + positions=grid_transforms(4, 1.0, device=sim.cfg.device)[0], + ) + + assert plan.sources == ("/World/envs/env_0",) + assert plan.destinations == ("/World/envs/env_{}",) + assert plan.cfg_rows == {id(env_cfg_a): (0,), id(env_cfg_b): (0,)} + assert plan.clone_mask.all() and plan.clone_mask.shape == (1, 4) + assert torch.equal(plan.env_ids, torch.arange(4, dtype=torch.long, device=sim.cfg.device)) + + +def test_replicate_drains_queue_dispatches_and_publishes(sim): + """replicate(plan) drains REPLICATION_QUEUE, calls each backend once, publishes, clears.""" + + class FakeCtx: + replicate_priority = 0 + instances: list["FakeCtx"] = [] + + def __init__(self, stage): + self.stage = stage + self.queue_calls: list[tuple] = [] + self.replicate_calls = 0 + FakeCtx.instances.append(self) + + def queue_mapping(self, sources, destinations, env_ids, mask, *, positions=None): + self.queue_calls.append((tuple(sources), tuple(destinations), mask.clone())) + + def replicate(self): + self.replicate_calls += 1 + + cfg_a = SimpleNamespace(prim_path="/World/envs/env_.*/Robot") + cfg_b = SimpleNamespace(prim_path="/World/envs/env_.*/Object") + REPLICATION_QUEUE.append((cfg_a, FakeCtx)) + REPLICATION_QUEUE.append((cfg_b, FakeCtx)) + + plan = ClonePlan( + sources=("/World/envs/env_0/Robot", "/World/envs/env_0/Object"), + destinations=("/World/envs/env_{}/Robot", "/World/envs/env_{}/Object"), + clone_mask=torch.ones((2, 4), dtype=torch.bool, device=sim.cfg.device), + env_ids=torch.arange(4, dtype=torch.long, device=sim.cfg.device), + positions=grid_transforms(4, 1.0, device=sim.cfg.device)[0], + cfg_rows={id(cfg_a): (0,), id(cfg_b): (1,)}, + ) + sim.set_clone_plan(None) + + replicate(plan, stage=sim_utils.get_current_stage()) + + # Exactly one FakeCtx instance is shared across both cfgs, dispatched once per backend + # with the union of rows the cfgs own. + assert len(FakeCtx.instances) == 1 + ctx = FakeCtx.instances[0] + assert len(ctx.queue_calls) == 1 + sources, _destinations, mask = ctx.queue_calls[0] + assert sources == ("/World/envs/env_0/Robot", "/World/envs/env_0/Object") + assert mask.shape == (2, 4) + assert ctx.replicate_calls == 1 + assert sim.get_clone_plan() is plan + assert REPLICATION_QUEUE == [] + + +def test_replicate_dedupes_shared_rows_across_cfgs(sim): + """Regression: multiple cfgs sharing the same row dispatch one mapping row, not N. + + In a homogeneous plan every cfg under the env root maps to row 0; without dedup, each + cfg would tell the backend to re-instantiate row 0 once more, multiplying the count + of articulations/rigids per world by the number of cfgs. + """ + + class FakeCtx: + replicate_priority = 0 + instances: list["FakeCtx"] = [] + + def __init__(self, stage): + self.queue_calls: list[tuple] = [] + self.replicate_calls = 0 + FakeCtx.instances.append(self) + + def queue_mapping(self, sources, destinations, env_ids, mask, *, positions=None): + self.queue_calls.append((tuple(sources), tuple(destinations), mask.clone())) + + def replicate(self): + self.replicate_calls += 1 + + cfgs = [SimpleNamespace(prim_path=f"/World/envs/env_.*/asset_{i}") for i in range(5)] + for cfg in cfgs: + REPLICATION_QUEUE.append((cfg, FakeCtx)) + + plan = ClonePlan( + sources=("/World/envs/env_0",), + destinations=("/World/envs/env_{}",), + clone_mask=torch.ones((1, 3), dtype=torch.bool, device=sim.cfg.device), + env_ids=torch.arange(3, dtype=torch.long, device=sim.cfg.device), + positions=grid_transforms(3, 1.0, device=sim.cfg.device)[0], + cfg_rows={id(cfg): (0,) for cfg in cfgs}, + ) + + replicate(plan, stage=sim_utils.get_current_stage()) + + assert len(FakeCtx.instances) == 1 + ctx = FakeCtx.instances[0] + assert len(ctx.queue_calls) == 1, "shared rows should collapse to one queue_mapping per backend" + sources, _destinations, mask = ctx.queue_calls[0] + assert sources == ("/World/envs/env_0",) + assert mask.shape == (1, 3) + assert ctx.replicate_calls == 1 + + +def test_replicate_runs_lower_priority_backends_first(sim): + """Sort order: lower replicate_priority runs first (physics before USD).""" + + call_order: list[str] = [] + + class LowPriority: + replicate_priority = 0 + + def __init__(self, stage): + pass + + def queue_mapping(self, *args, **kwargs): + pass + + def replicate(self): + call_order.append("low") + + class HighPriority: + replicate_priority = 100 + + def __init__(self, stage): + pass + + def queue_mapping(self, *args, **kwargs): + pass + + def replicate(self): + call_order.append("high") + + cfg = SimpleNamespace(prim_path="/World/envs/env_.*/Robot") + REPLICATION_QUEUE.append((cfg, HighPriority)) + REPLICATION_QUEUE.append((cfg, LowPriority)) + + plan = ClonePlan( + sources=("/World/envs/env_0",), + destinations=("/World/envs/env_{}",), + clone_mask=torch.ones((1, 2), dtype=torch.bool, device=sim.cfg.device), + env_ids=torch.arange(2, dtype=torch.long, device=sim.cfg.device), + positions=None, + cfg_rows={id(cfg): (0,)}, + ) + replicate(plan, stage=sim_utils.get_current_stage()) + + assert call_order == ["low", "high"] + + +def test_replicate_skips_cfgs_not_in_plan(sim): + """Cfgs absent from plan.cfg_rows are silently skipped.""" + sentinel = MagicMock() + sentinel.replicate_priority = 0 + sentinel.replicate.side_effect = lambda: None + sentinel_cls = MagicMock(return_value=sentinel) + + excluded_cfg = SimpleNamespace(prim_path="/World/global/Skip") + REPLICATION_QUEUE.append((excluded_cfg, sentinel_cls)) + + plan = ClonePlan( + sources=("/World/envs/env_0",), + destinations=("/World/envs/env_{}",), + clone_mask=torch.ones((1, 2), dtype=torch.bool, device=sim.cfg.device), + env_ids=torch.arange(2, dtype=torch.long, device=sim.cfg.device), + positions=None, + cfg_rows={}, + ) + replicate(plan, stage=sim_utils.get_current_stage()) + + sentinel_cls.assert_not_called() + + +def test_replicate_clears_queue_on_backend_failure(sim): + """REPLICATION_QUEUE is drained even when a backend ctx raises mid-dispatch.""" + + class ExplodingCtx: + replicate_priority = 0 + + def __init__(self, stage): + pass + + def queue_mapping(self, *args, **kwargs): + pass + + def replicate(self): + raise RuntimeError("backend boom") + + cfg = SimpleNamespace(prim_path="/World/envs/env_.*/Robot") + REPLICATION_QUEUE.append((cfg, ExplodingCtx)) + + plan = ClonePlan( + sources=("/World/envs/env_0",), + destinations=("/World/envs/env_{}",), + clone_mask=torch.ones((1, 2), dtype=torch.bool, device=sim.cfg.device), + env_ids=torch.arange(2, dtype=torch.long, device=sim.cfg.device), + positions=None, + cfg_rows={id(cfg): (0,)}, + ) + + with pytest.raises(RuntimeError, match="backend boom"): + replicate(plan, stage=sim_utils.get_current_stage()) + + assert REPLICATION_QUEUE == [] + + +def test_replicate_session_clears_queue_when_asset_init_fails(sim): + """ReplicateSession.__exit__ drops queued cfgs if the asset constructor body raises.""" + from isaaclab.cloner import ReplicateSession + + leaked_cfg = SimpleNamespace(prim_path="/World/envs/env_.*/Robot") + + sentinel = MagicMock() + sentinel_cls = MagicMock(return_value=sentinel) + + with pytest.raises(RuntimeError, match="asset boom"): + with ReplicateSession( + cfgs=[], + num_clones=2, + env_spacing=1.0, + device=sim.cfg.device, + stage=sim_utils.get_current_stage(), + ): + REPLICATION_QUEUE.append((leaked_cfg, sentinel_cls)) + raise RuntimeError("asset boom") + + assert REPLICATION_QUEUE == [] + sentinel_cls.assert_not_called() + + +def test_iter_clone_plan_matches(sim): + """ClonePlan entries can be matched by destination path expression.""" + plan = ClonePlan( + sources=("/World/envs/env_0/Object", "/World/envs/env_1/Object"), + destinations=("/World/envs/env_{}/Object", "/World/envs/env_{}/Object"), + clone_mask=torch.tensor( + [[True, False, True, False], [False, True, False, True]], + dtype=torch.bool, + device=sim.cfg.device, + ), ) - plan = ClonePlan(sources=sources, destinations=destinations, clone_mask=clone_mask) matches = list(iter_clone_plan_matches(plan, "/World/envs/env_.*/Object/Body/Camera")) diff --git a/source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst b/source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst new file mode 100644 index 000000000000..a06cc9ca40af --- /dev/null +++ b/source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed Newton deformable clone replication and Fabric particle sync setup. diff --git a/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_featherstone_vbd_manager.py b/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_featherstone_vbd_manager.py index 19e5aa62cee6..b47371b4ec65 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_featherstone_vbd_manager.py +++ b/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_featherstone_vbd_manager.py @@ -23,6 +23,7 @@ add_deformable_entry_to_builder, clear_deformable_builder_hooks, install_deformable_builder_hooks, + setup_registered_deformable_fabric_sync, ) from .kernels import _kernel_body_particle_reaction from .newton_manager_cfg import CoupledFeatherstoneVBDSolverCfg @@ -145,41 +146,7 @@ def start_simulation(cls) -> None: model.shape_material_mu.fill_(float(model_cfg.shape_material_mu)) # Setup USD/Fabric sync for Kit viewport deformable rendering - if not cls._clone_physics_only and cls._deformable_registry: - import re - - import usdrt - - if NewtonManager._usdrt_stage is None: - NewtonManager._usdrt_stage = get_current_stage(fabric=True) - - stage = get_current_stage() - for entry in cls._deformable_registry: - for inst_idx, offset in enumerate(entry.particle_offsets): - # Resolve regex pattern to concrete instance path of visual mesh - resolved_vis = re.sub(r"(?<=[Ee]nv_)\.\*", str(inst_idx), entry.vis_mesh_prim_path) - resolved_vis = re.sub(r"\.\*", str(inst_idx), resolved_vis) - vis_prim = stage.GetPrimAtPath(resolved_vis) - - if not vis_prim or not vis_prim.IsValid(): - logger.warning("[setup_fabric_particle_sync] vis prim not found at %s", resolved_vis) - continue - - # Create per-instance particle offset and count attributes on the visual mesh - # prim so the Fabric sync kernel can find the right slice of particle_q - # and iterate only over this body's particles (counts vary across bodies). - fab_prim = NewtonManager._usdrt_stage.GetPrimAtPath(vis_prim.GetPath().pathString) - fab_prim.CreateAttribute( - NewtonManager._newton_particle_offset_attr, usdrt.Sdf.ValueTypeNames.UInt, True - ) - fab_prim.GetAttribute(NewtonManager._newton_particle_offset_attr).Set(offset) - fab_prim.CreateAttribute( - NewtonManager._newton_particle_count_attr, usdrt.Sdf.ValueTypeNames.UInt, True - ) - fab_prim.GetAttribute(NewtonManager._newton_particle_count_attr).Set(entry.particles_per_body) - - cls._mark_particles_dirty() - cls.sync_particles_to_usd() + setup_registered_deformable_fabric_sync(cls) @classmethod def instantiate_builder_from_stage(cls): diff --git a/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_mjwarp_vbd_manager.py b/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_mjwarp_vbd_manager.py index dd288f4347f3..8faf468dee8c 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_mjwarp_vbd_manager.py +++ b/source/isaaclab_contrib/isaaclab_contrib/deformable/coupled_mjwarp_vbd_manager.py @@ -23,6 +23,7 @@ add_deformable_entry_to_builder, clear_deformable_builder_hooks, install_deformable_builder_hooks, + setup_registered_deformable_fabric_sync, ) from .kernels import _kernel_body_particle_reaction from .newton_manager_cfg import CoupledMJWarpVBDSolverCfg @@ -145,41 +146,7 @@ def start_simulation(cls) -> None: model.shape_material_mu.fill_(float(model_cfg.shape_material_mu)) # Setup USD/Fabric sync for Kit viewport deformable rendering - if not cls._clone_physics_only and cls._deformable_registry: - import re - - import usdrt - - if NewtonManager._usdrt_stage is None: - NewtonManager._usdrt_stage = get_current_stage(fabric=True) - - stage = get_current_stage() - for entry in cls._deformable_registry: - for inst_idx, offset in enumerate(entry.particle_offsets): - # Resolve regex pattern to concrete instance path of visual mesh - resolved_vis = re.sub(r"(?<=[Ee]nv_)\.\*", str(inst_idx), entry.vis_mesh_prim_path) - resolved_vis = re.sub(r"\.\*", str(inst_idx), resolved_vis) - vis_prim = stage.GetPrimAtPath(resolved_vis) - - if not vis_prim or not vis_prim.IsValid(): - logger.warning("[setup_fabric_particle_sync] vis prim not found at %s", resolved_vis) - continue - - # Create per-instance particle offset and count attributes on the visual mesh - # prim so the Fabric sync kernel can find the right slice of particle_q - # and iterate only over this body's particles (counts vary across bodies). - fab_prim = NewtonManager._usdrt_stage.GetPrimAtPath(vis_prim.GetPath().pathString) - fab_prim.CreateAttribute( - NewtonManager._newton_particle_offset_attr, usdrt.Sdf.ValueTypeNames.UInt, True - ) - fab_prim.GetAttribute(NewtonManager._newton_particle_offset_attr).Set(offset) - fab_prim.CreateAttribute( - NewtonManager._newton_particle_count_attr, usdrt.Sdf.ValueTypeNames.UInt, True - ) - fab_prim.GetAttribute(NewtonManager._newton_particle_count_attr).Set(entry.particles_per_body) - - cls._mark_particles_dirty() - cls.sync_particles_to_usd() + setup_registered_deformable_fabric_sync(cls) @classmethod def instantiate_builder_from_stage(cls): diff --git a/source/isaaclab_contrib/isaaclab_contrib/deformable/deformable_object.py b/source/isaaclab_contrib/isaaclab_contrib/deformable/deformable_object.py index 3c7fd10eb03e..6da958b639d8 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/deformable/deformable_object.py +++ b/source/isaaclab_contrib/isaaclab_contrib/deformable/deformable_object.py @@ -13,10 +13,12 @@ import numpy as np import torch import warp as wp +from isaaclab_newton.cloner import queue_newton_physics_replication from isaaclab_newton.physics import NewtonManager as SimulationManager import isaaclab.sim as sim_utils from isaaclab.assets.deformable_object.base_deformable_object import BaseDeformableObject +from isaaclab.cloner import queue_usd_replication from isaaclab.markers import VisualizationMarkers from isaaclab.physics import PhysicsEvent from isaaclab.utils.warp import ProxyArray @@ -187,6 +189,62 @@ def color_registered_deformables(builder) -> None: builder.color() +def setup_registered_deformable_fabric_sync(manager_cls: type[SimulationManager]) -> None: + """Bind registered deformable visual meshes to their Newton particle slices in Fabric.""" + if manager_cls._clone_physics_only or not manager_cls._deformable_registry: + return + + import re + + import usdrt + + from isaaclab.sim.utils.stage import get_current_stage + + if SimulationManager._usdrt_stage is None: + SimulationManager._usdrt_stage = get_current_stage(fabric=True) + fabric_stage = SimulationManager._usdrt_stage + if fabric_stage is None: + logger.warning("[setup_fabric_particle_sync] Fabric stage is unavailable.") + return + + stage = get_current_stage() + synced_any = False + for entry in manager_cls._deformable_registry: + for inst_idx, offset in enumerate(entry.particle_offsets): + resolved_vis = re.sub(r"(?<=[Ee]nv_)\.\*", str(inst_idx), entry.vis_mesh_prim_path) + resolved_vis = re.sub(r"\.\*", str(inst_idx), resolved_vis) + vis_prim = stage.GetPrimAtPath(resolved_vis) + + if not vis_prim or not vis_prim.IsValid(): + logger.warning("[setup_fabric_particle_sync] vis prim not found at %s", resolved_vis) + continue + + fab_prim = fabric_stage.GetPrimAtPath(vis_prim.GetPath().pathString) + if not fab_prim or not fab_prim.IsValid(): + logger.warning("[setup_fabric_particle_sync] Fabric prim not found at %s", resolved_vis) + continue + + offset_attr = fab_prim.CreateAttribute( + SimulationManager._newton_particle_offset_attr, usdrt.Sdf.ValueTypeNames.UInt, True + ) + count_attr = fab_prim.CreateAttribute( + SimulationManager._newton_particle_count_attr, usdrt.Sdf.ValueTypeNames.UInt, True + ) + if not offset_attr.IsValid() or not count_attr.IsValid(): + logger.warning( + "[setup_fabric_particle_sync] Fabric particle attributes not created at %s", resolved_vis + ) + continue + + offset_attr.Set(int(offset)) + count_attr.Set(int(entry.particles_per_body)) + synced_any = True + + if synced_any: + manager_cls._mark_particles_dirty() + manager_cls.sync_particles_to_usd() + + def install_deformable_builder_hooks() -> None: """Install deformable builder hooks without removing hooks owned by other extensions.""" SimulationManager._deformable_registry = [] @@ -241,6 +299,8 @@ def __init__(self, cfg: DeformableObjectCfg): cfg: A configuration instance. """ super().__init__(cfg) + queue_usd_replication(cfg) + queue_newton_physics_replication(cfg) # initialize deformable type to None, should be set to either surface or volume on initialization self._deformable_type: str | None = None diff --git a/source/isaaclab_contrib/isaaclab_contrib/deformable/vbd_manager.py b/source/isaaclab_contrib/isaaclab_contrib/deformable/vbd_manager.py index 48c31b06e4f1..58a2f3bfadd9 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/deformable/vbd_manager.py +++ b/source/isaaclab_contrib/isaaclab_contrib/deformable/vbd_manager.py @@ -23,6 +23,7 @@ add_deformable_entry_to_builder, clear_deformable_builder_hooks, install_deformable_builder_hooks, + setup_registered_deformable_fabric_sync, ) from .newton_manager_cfg import VBDSolverCfg @@ -120,41 +121,7 @@ def start_simulation(cls) -> None: model.shape_material_mu.fill_(float(model_cfg.shape_material_mu)) # Setup USD/Fabric sync for Kit viewport deformable rendering - if not cls._clone_physics_only and cls._deformable_registry: - import re - - import usdrt - - if NewtonManager._usdrt_stage is None: - NewtonManager._usdrt_stage = get_current_stage(fabric=True) - - stage = get_current_stage() - for entry in cls._deformable_registry: - for inst_idx, offset in enumerate(entry.particle_offsets): - # Resolve regex pattern to concrete instance path of visual mesh - resolved_vis = re.sub(r"(?<=[Ee]nv_)\.\*", str(inst_idx), entry.vis_mesh_prim_path) - resolved_vis = re.sub(r"\.\*", str(inst_idx), resolved_vis) - vis_prim = stage.GetPrimAtPath(resolved_vis) - - if not vis_prim or not vis_prim.IsValid(): - logger.warning("[setup_fabric_particle_sync] vis prim not found at %s", resolved_vis) - continue - - # Create per-instance particle offset and count attributes on the visual mesh - # prim so the Fabric sync kernel can find the right slice of particle_q - # and iterate only over this body's particles (counts vary across bodies). - fab_prim = NewtonManager._usdrt_stage.GetPrimAtPath(vis_prim.GetPath().pathString) - fab_prim.CreateAttribute( - NewtonManager._newton_particle_offset_attr, usdrt.Sdf.ValueTypeNames.UInt, True - ) - fab_prim.GetAttribute(NewtonManager._newton_particle_offset_attr).Set(offset) - fab_prim.CreateAttribute( - NewtonManager._newton_particle_count_attr, usdrt.Sdf.ValueTypeNames.UInt, True - ) - fab_prim.GetAttribute(NewtonManager._newton_particle_count_attr).Set(entry.particles_per_body) - - cls._mark_particles_dirty() - cls.sync_particles_to_usd() + setup_registered_deformable_fabric_sync(cls) @classmethod def instantiate_builder_from_stage(cls): diff --git a/source/isaaclab_contrib/test/deformable/test_deformable_builder_hooks.py b/source/isaaclab_contrib/test/deformable/test_deformable_builder_hooks.py index 4a9c03932c5b..3c3570c7e5e6 100644 --- a/source/isaaclab_contrib/test/deformable/test_deformable_builder_hooks.py +++ b/source/isaaclab_contrib/test/deformable/test_deformable_builder_hooks.py @@ -4,13 +4,25 @@ # SPDX-License-Identifier: BSD-3-Clause import math +import sys +from types import SimpleNamespace import pytest import warp as wp +from isaaclab_newton.cloner.replicate import NewtonReplicateContext +from isaaclab_newton.physics import NewtonManager from isaaclab_newton.sim.spawners.materials import NewtonDeformableMaterialCfg +from isaaclab.assets.deformable_object.base_deformable_object import BaseDeformableObject +from isaaclab.cloner.replicate_session import REPLICATION_QUEUE +from isaaclab.cloner.usd import UsdReplicateContext + from isaaclab_contrib.deformable import DeformableObject, VBDSolverCfg -from isaaclab_contrib.deformable.deformable_object import DeformableRegistryEntry, add_deformable_entry_to_builder +from isaaclab_contrib.deformable.deformable_object import ( + DeformableRegistryEntry, + add_deformable_entry_to_builder, + setup_registered_deformable_fabric_sync, +) class _FakeBuilder: @@ -23,6 +35,31 @@ def add_cloth_mesh(self, **kwargs) -> None: self.particle_count += len(kwargs["vertices"]) +class _FakePath: + def __init__(self, path: str): + self.pathString = path + + +class _FakePrim: + def __init__(self, path: str, *, valid: bool = True): + self._path = path + self._valid = valid + + def IsValid(self) -> bool: + return self._valid + + def GetPath(self) -> _FakePath: + return _FakePath(self._path) + + +class _FakeStage: + def __init__(self, prims: dict[str, _FakePrim]): + self._prims = prims + + def GetPrimAtPath(self, path: str) -> _FakePrim: + return self._prims.get(path, _FakePrim(path, valid=False)) + + def _make_surface_entry() -> DeformableRegistryEntry: half_sqrt = math.sqrt(0.5) return DeformableRegistryEntry( @@ -98,3 +135,67 @@ def test_builder_hook_resets_entry_offsets_on_first_environment(): assert entry.particle_offsets == [0] assert entry.particles_per_body == 3 + + +def test_newton_deformable_queues_usd_and_newton_replication(monkeypatch): + """Test that Newton deformables participate in both clone products.""" + cfg = SimpleNamespace() + + def fake_base_init(self, cfg): + self.cfg = cfg + self._DTYPE_TO_TORCH_TRAILING_DIMS = {} + self._initialize_handle = None + self._invalidate_initialize_handle = None + self._prim_deletion_handle = None + self._debug_vis_handle = None + self._physics_ready_handle = None + + monkeypatch.setattr(BaseDeformableObject, "__init__", fake_base_init) + monkeypatch.setattr(DeformableObject, "_register_deformable", lambda self: object()) + REPLICATION_QUEUE.clear() + + try: + DeformableObject(cfg) + queued_contexts = [ctx_cls for queued_cfg, ctx_cls in REPLICATION_QUEUE if queued_cfg is cfg] + finally: + REPLICATION_QUEUE.clear() + + assert queued_contexts == [UsdReplicateContext, NewtonReplicateContext] + + +def test_fabric_particle_sync_skips_missing_fabric_prim(monkeypatch): + """Test that missing Fabric prims are skipped before attributes are authored.""" + entry = _make_surface_entry() + entry.particle_offsets = [7] + entry.particles_per_body = 3 + resolved_path = "/World/envs/env_0/cloth/mesh" + + class _FakeManager: + _clone_physics_only = False + _deformable_registry = [entry] + marked = False + synced = False + + @classmethod + def _mark_particles_dirty(cls): + cls.marked = True + + @classmethod + def sync_particles_to_usd(cls): + cls.synced = True + + usd_stage = _FakeStage({resolved_path: _FakePrim(resolved_path)}) + fabric_stage = _FakeStage({}) + + monkeypatch.setattr( + "isaaclab.sim.utils.stage.get_current_stage", lambda fabric=False: fabric_stage if fabric else usd_stage + ) + monkeypatch.setattr(NewtonManager, "_usdrt_stage", fabric_stage) + monkeypatch.setitem( + sys.modules, "usdrt", SimpleNamespace(Sdf=SimpleNamespace(ValueTypeNames=SimpleNamespace(UInt=object()))) + ) + + setup_registered_deformable_fabric_sync(_FakeManager) + + assert not _FakeManager.marked + assert not _FakeManager.synced diff --git a/source/isaaclab_newton/changelog.d/replication-session-redesign.skip b/source/isaaclab_newton/changelog.d/replication-session-redesign.skip new file mode 100644 index 000000000000..4ff1bbe80281 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/replication-session-redesign.skip @@ -0,0 +1,5 @@ +Internal refactor: ``queue_newton_physics_replication`` now appends ``(cfg, +NewtonReplicateContext)`` to :data:`isaaclab.cloner.REPLICATION_QUEUE` instead of +reaching into the now-removed module-level replication session. No user-visible +behavior change — :func:`~isaaclab.cloner.replicate` still drives Newton replication +via :class:`NewtonReplicateContext` exactly as before. diff --git a/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py b/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py index a5ebaffd09fe..b1f895ab4e0a 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation.py @@ -38,6 +38,7 @@ from isaaclab_newton.assets import kernels as shared_kernels from isaaclab_newton.assets.articulation import kernels as articulation_kernels +from isaaclab_newton.cloner import queue_newton_physics_replication from isaaclab_newton.physics import NewtonManager as SimulationManager from .articulation_data import ArticulationData @@ -121,6 +122,7 @@ def __init__(self, cfg: ArticulationCfg): from isaaclab.sim import SimulationContext # noqa: PLC0415 super().__init__(cfg) + queue_newton_physics_replication(cfg) sim_ctx = SimulationContext.instance() self._sim_cfg = sim_ctx.cfg if sim_ctx is not None else None diff --git a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py index d61beebc92f6..2709609e0f4f 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py @@ -24,6 +24,7 @@ from isaaclab.utils.wrench_composer import WrenchComposer from isaaclab_newton.assets import kernels as shared_kernels +from isaaclab_newton.cloner import queue_newton_physics_replication from isaaclab_newton.physics import NewtonManager as SimulationManager from .rigid_object_data import RigidObjectData @@ -59,6 +60,7 @@ def __init__(self, cfg: RigidObjectCfg): cfg: A configuration instance. """ super().__init__(cfg) + queue_newton_physics_replication(cfg) """ Properties diff --git a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py index 389d3cf89d69..316b302de2cb 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object_collection/rigid_object_collection.py @@ -25,6 +25,7 @@ from isaaclab.utils.wrench_composer import WrenchComposer from isaaclab_newton.assets import kernels as shared_kernels +from isaaclab_newton.cloner import queue_newton_physics_replication from isaaclab_newton.physics import NewtonManager as SimulationManager from .rigid_object_collection_data import RigidObjectCollectionData @@ -75,7 +76,8 @@ def __init__(self, cfg: RigidObjectCollectionCfg): # flag for whether the asset is initialized self._is_initialized = False # spawn the rigid objects - for rigid_body_cfg in self.cfg.rigid_objects.values(): + source_rigid_object_cfgs = cfg.rigid_objects + for rigid_body_name, rigid_body_cfg in self.cfg.rigid_objects.items(): # spawn the asset if rigid_body_cfg.spawn is not None: spawn_path = rigid_body_cfg.spawn.spawn_path or rigid_body_cfg.prim_path @@ -89,6 +91,7 @@ def __init__(self, cfg: RigidObjectCollectionCfg): matching_prims = sim_utils.find_matching_prims(rigid_body_cfg.prim_path) if len(matching_prims) == 0: raise RuntimeError(f"Could not find prim with path {rigid_body_cfg.prim_path}.") + queue_newton_physics_replication(source_rigid_object_cfgs[rigid_body_name]) # stores object names self._body_names_list = [] diff --git a/source/isaaclab_newton/isaaclab_newton/cloner/__init__.pyi b/source/isaaclab_newton/isaaclab_newton/cloner/__init__.pyi index f55377295a3e..8bb3102fa395 100644 --- a/source/isaaclab_newton/isaaclab_newton/cloner/__init__.pyi +++ b/source/isaaclab_newton/isaaclab_newton/cloner/__init__.pyi @@ -4,8 +4,13 @@ # SPDX-License-Identifier: BSD-3-Clause __all__ = [ + "NewtonReplicateContext", "newton_physics_replicate", - "newton_visualizer_prebuild", + "queue_newton_physics_replication", ] -from .newton_replicate import newton_physics_replicate, newton_visualizer_prebuild +from .replicate import ( + NewtonReplicateContext, + newton_physics_replicate, + queue_newton_physics_replication, +) diff --git a/source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py b/source/isaaclab_newton/isaaclab_newton/cloner/replicate.py similarity index 63% rename from source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py rename to source/isaaclab_newton/isaaclab_newton/cloner/replicate.py index e868607c05c5..2b13e7cef787 100644 --- a/source/isaaclab_newton/isaaclab_newton/cloner/newton_replicate.py +++ b/source/isaaclab_newton/isaaclab_newton/cloner/replicate.py @@ -6,6 +6,7 @@ from __future__ import annotations from collections.abc import Sequence +from typing import Any import torch import warp as wp @@ -14,6 +15,8 @@ from pxr import Usd +from isaaclab.cloner.replicate_session import REPLICATION_QUEUE + from isaaclab_newton.physics import NewtonManager @@ -26,7 +29,7 @@ def _build_newton_builder_from_mapping( quaternions: torch.Tensor | None = None, up_axis: str = "Z", simplify_meshes: bool = True, -) -> tuple[ModelBuilder, object, dict]: +) -> tuple[ModelBuilder, object, dict, list]: """Build a Newton model builder from clone mapping inputs. Args: @@ -41,8 +44,9 @@ def _build_newton_builder_from_mapping( Returns: Tuple of the populated Newton model builder, stage metadata returned - by ``add_usd``, and a site index map for - :attr:`NewtonManager._cl_site_index_map`. + by ``add_usd``, a site index map for + :attr:`NewtonManager._cl_site_index_map`, and the absolute per-world + transforms for :attr:`NewtonManager._world_xforms`. """ if positions is None: positions = torch.zeros((mapping.size(1), 3), device=mapping.device, dtype=torch.float32) @@ -106,26 +110,35 @@ def _build_newton_builder_from_mapping( # Local sites: per-world sublists, populated in the loop below num_worlds = mapping.size(1) local_site_map: dict[str, list[list[int]]] = {} + # Absolute per-world transforms (env-root local-to-world). Consumed by + # FrameView to place non-physics frames (e.g. cameras) relative to each + # cloned env, mirroring the legacy ``_replicate_from_stage`` path. + world_xforms: list[wp.transform] = [] # create a separate world for each environment (heterogeneous spawning) # Newton assigns sequential world IDs (0, 1, 2, ...), so we need to track the mapping for col, _ in enumerate(env_ids.tolist()): # begin a new world context (Newton assigns world ID = col) builder.begin_world() - # add all active sources for this world + # ``add_builder`` xforms are deltas from env_0 (the proto is baked in env_0's + # absolute coords), while bodyless world sites and ``world_xforms`` live in the + # global frame and therefore use the env's absolute transform. delta_pos = (positions[col] - env0_pos).tolist() - env_xform = wp.transform(positions[col].tolist(), quaternions[col].tolist()) + env_xform = wp.transform(delta_pos, quaternions[col].tolist()) + world_xform = wp.transform(positions[col].tolist(), quaternions[col].tolist()) + world_xforms.append(world_xform) + # Per-world bodyless sites are placed in each world's (global) frame. for label, xform in world_sites.items(): if label not in local_site_map: local_site_map[label] = [[] for _ in range(num_worlds)] - site_idx = builder.add_site(body=-1, xform=wp.transform_multiply(env_xform, xform), label=label) + site_idx = builder.add_site(body=-1, xform=wp.transform_multiply(world_xform, xform), label=label) local_site_map[label][col].append(site_idx) for row in torch.nonzero(mapping[:, col], as_tuple=True)[0].tolist(): proto = protos[sources[row]] offset = builder.shape_count builder.add_builder( proto, - xform=wp.transform(delta_pos, quaternions[col].tolist()), + xform=env_xform, ) # Compute final shape indices for sites in this proto for label, proto_shape_indices in proto_sites.get(id(proto), {}).items(): @@ -152,7 +165,7 @@ def _build_newton_builder_from_mapping( **{label: (None, per_world) for label, per_world in local_site_map.items()}, } - return builder, stage_info, site_index_map + return builder, stage_info, site_index_map, world_xforms # Built-in label arrays that ``_rename_builder_labels`` rewrites in Pass 1. @@ -262,6 +275,149 @@ def _rename_pair(values, worlds): _rename_pair(values, worlds) +class NewtonReplicateContext: + """Queue and run Newton replication work for one stage.""" + + def __init__( + self, + stage: Usd.Stage, + *, + device: str = "cpu", + up_axis: str = "Z", + simplify_meshes: bool = True, + commit_to_manager: bool = True, + ): + """Initialize the context. + + Args: + stage: USD stage containing source assets. + device: Device used by the finalized Newton model builder. + up_axis: Up axis for the Newton model builder. + simplify_meshes: Whether to run convex-hull mesh approximation. + commit_to_manager: Whether :meth:`replicate` should publish the builder to + :class:`NewtonManager`. + """ + self.stage = stage + self.device = device + self.up_axis = up_axis + self.simplify_meshes = simplify_meshes + self.commit_to_manager = commit_to_manager + self._queue: list[ + tuple[ + tuple[str, ...], + tuple[str, ...], + torch.Tensor, + torch.Tensor, + torch.Tensor | None, + torch.Tensor | None, + ] + ] = [] + + def queue_mapping( + self, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mapping: torch.Tensor, + *, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + ) -> None: + """Queue replication rows from the current flat clone mapping. + + Args: + sources: Source prim paths used for cloning. + destinations: Destination prim path templates. + env_ids: Environment ids for destination worlds. + mapping: Boolean source-to-environment mapping matrix. + positions: Optional per-environment world positions [m]. + quaternions: Optional per-environment orientations in xyzw order. + """ + self._queue.append((tuple(sources), tuple(destinations), env_ids, mapping, positions, quaternions)) + + @staticmethod + def _merge_optional_tensor( + name: str, current: torch.Tensor | None, incoming: torch.Tensor | None + ) -> torch.Tensor | None: + """Merge optional tensors, requiring equal values when both are present.""" + if current is None: + return incoming + if incoming is None: + return current + if current.device != incoming.device or current.shape != incoming.shape or not torch.equal(current, incoming): + raise ValueError(f"Queued Newton mappings must use the same {name} tensor.") + return current + + def _merged_mapping( + self, + ) -> tuple[tuple[str, ...], tuple[str, ...], torch.Tensor, torch.Tensor, torch.Tensor | None, torch.Tensor | None]: + """Merge queued mapping batches into the legacy flat mapping shape.""" + if not self._queue: + raise RuntimeError("Cannot replicate without queued Newton mappings.") + + sources: list[str] = [] + destinations: list[str] = [] + mappings: list[torch.Tensor] = [] + env_ids = self._queue[0][2] + positions = self._queue[0][4] + quaternions = self._queue[0][5] + + for ( + queued_sources, + queued_destinations, + queued_env_ids, + mapping, + queued_positions, + queued_quaternions, + ) in self._queue: + if ( + env_ids.device != queued_env_ids.device + or env_ids.shape != queued_env_ids.shape + or not torch.equal(env_ids, queued_env_ids) + ): + raise ValueError("Queued Newton mappings must use the same env_ids tensor.") + sources.extend(queued_sources) + destinations.extend(queued_destinations) + mappings.append(mapping) + positions = self._merge_optional_tensor("positions", positions, queued_positions) + quaternions = self._merge_optional_tensor("quaternions", quaternions, queued_quaternions) + + return tuple(sources), tuple(destinations), env_ids, torch.cat(mappings, dim=0), positions, quaternions + + def replicate(self) -> tuple[ModelBuilder, object, dict]: + """Build the Newton model builder from queued mappings and optionally publish it.""" + sources, destinations, env_ids, mapping, positions, quaternions = self._merged_mapping() + builder, stage_info, site_index_map, world_xforms = _build_newton_builder_from_mapping( + stage=self.stage, + sources=sources, + env_ids=env_ids, + mapping=mapping, + positions=positions, + quaternions=quaternions, + up_axis=self.up_axis, + simplify_meshes=self.simplify_meshes, + ) + _rename_builder_labels(builder, sources, destinations, env_ids, mapping) + if self.commit_to_manager: + NewtonManager._cl_site_index_map = site_index_map + NewtonManager._world_xforms = world_xforms + NewtonManager.set_builder(builder) + NewtonManager._num_envs = mapping.size(1) + self._queue.clear() + return builder, stage_info, site_index_map + + +def queue_newton_physics_replication(cfg: Any) -> None: + """Register ``cfg`` for Newton replication when :func:`~isaaclab.cloner.replicate` next runs. + + Appends ``(cfg, NewtonReplicateContext)`` to + :data:`~isaaclab.cloner.REPLICATION_QUEUE`. The actual row resolution and dispatch + happen inside :func:`~isaaclab.cloner.replicate`, so this helper is safe to call from + any asset constructor — no active session is required. + """ + REPLICATION_QUEUE.append((cfg, NewtonReplicateContext)) + + def newton_physics_replicate( stage: Usd.Stage, sources: Sequence[str], @@ -291,75 +447,16 @@ def newton_physics_replicate( Returns: Tuple of the populated Newton model builder and stage metadata. """ - if positions is None: - positions = torch.zeros((mapping.size(1), 3), device=mapping.device, dtype=torch.float32) - if quaternions is None: - quaternions = torch.zeros((mapping.size(1), 4), device=mapping.device, dtype=torch.float32) - quaternions[:, 3] = 1.0 - - builder, stage_info, site_index_map = _build_newton_builder_from_mapping( - stage=stage, - sources=sources, - env_ids=env_ids, - mapping=mapping, - positions=positions, - quaternions=quaternions, - up_axis=up_axis, - simplify_meshes=simplify_meshes, + ctx = NewtonReplicateContext( + stage, device=device, up_axis=up_axis, simplify_meshes=simplify_meshes, commit_to_manager=True ) - _rename_builder_labels(builder, sources, destinations, env_ids, mapping) - NewtonManager._cl_site_index_map = site_index_map - NewtonManager._world_xforms = [ - wp.transform(positions[col].tolist(), quaternions[col].tolist()) for col in range(mapping.size(1)) - ] - NewtonManager.set_builder(builder) - NewtonManager._num_envs = mapping.size(1) - return builder, stage_info - - -def newton_visualizer_prebuild( - stage: Usd.Stage, - sources: Sequence[str], - destinations: Sequence[str], - env_ids: torch.Tensor, - mapping: torch.Tensor, - positions: torch.Tensor | None = None, - quaternions: torch.Tensor | None = None, - device: str = "cpu", - up_axis: str = "Z", - simplify_meshes: bool = True, -): - """Replicate a clone plan into a finalized Newton model/state for visualization. - - Unlike :func:`newton_physics_replicate`, this path does not mutate ``NewtonManager`` and is intended - for prebuilding visualizer-only artifacts that can be consumed by scene data providers. - - Args: - stage: USD stage containing source assets. - sources: Source prim paths used for cloning. - destinations: Destination prim path templates. - env_ids: Environment ids for destination worlds. - mapping: Boolean source-to-environment mapping matrix. - positions: Optional per-environment world positions. - quaternions: Optional per-environment orientations in xyzw order. - device: Device used by the finalized Newton model. - up_axis: Up axis for the Newton model builder. - simplify_meshes: Whether to run convex-hull mesh approximation. - - Returns: - Tuple of finalized Newton model and state. - """ - builder, _, _site_index_map = _build_newton_builder_from_mapping( - stage=stage, - sources=sources, - env_ids=env_ids, - mapping=mapping, + ctx.queue_mapping( + sources, + destinations, + env_ids, + mapping, positions=positions, quaternions=quaternions, - up_axis=up_axis, - simplify_meshes=simplify_meshes, ) - _rename_builder_labels(builder, sources, destinations, env_ids, mapping) - model = builder.finalize(device=device) - state = model.state() - return model, state + builder, stage_info, _site_index_map = ctx.replicate() + return builder, stage_info diff --git a/source/isaaclab_newton/test/cloner/test_rename_builder_labels.py b/source/isaaclab_newton/test/cloner/test_rename_builder_labels.py index 5ecf162fbcab..f9913d58ec95 100644 --- a/source/isaaclab_newton/test/cloner/test_rename_builder_labels.py +++ b/source/isaaclab_newton/test/cloner/test_rename_builder_labels.py @@ -21,7 +21,7 @@ import newton import torch -from isaaclab_newton.cloner.newton_replicate import _BUILTIN_LABEL_TYPES, _rename_builder_labels +from isaaclab_newton.cloner.replicate import _BUILTIN_LABEL_TYPES, _rename_builder_labels from newton.solvers import SolverMuJoCo _TENDON_FREQ = "mujoco:tendon" diff --git a/source/isaaclab_ovphysx/changelog.d/replication-session-redesign.skip b/source/isaaclab_ovphysx/changelog.d/replication-session-redesign.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py index 96fa3c2ce20a..c075dc8c12a4 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py @@ -23,6 +23,7 @@ import isaaclab.sim as sim_utils from isaaclab.assets.articulation.articulation_cfg import ArticulationCfg from isaaclab.assets.articulation.base_articulation import BaseArticulation +from isaaclab.cloner import queue_usd_replication from isaaclab.physics import PhysicsManager from isaaclab.utils.string import resolve_matching_names from isaaclab.utils.wrench_composer import WrenchComposer @@ -30,6 +31,7 @@ from isaaclab_ovphysx import tensor_types as TT from isaaclab_ovphysx.assets import kernels as shared_kernels from isaaclab_ovphysx.assets.kernels import _body_wrench_to_world +from isaaclab_ovphysx.cloner import queue_ovphysx_replication from isaaclab_ovphysx.physics import OvPhysxManager from .articulation_data import ArticulationData @@ -84,6 +86,8 @@ def __init__(self, cfg: ArticulationCfg): cfg: A configuration instance. """ super().__init__(cfg) + queue_usd_replication(cfg) + queue_ovphysx_replication(cfg) # bindings are populated eagerly in ``_initialize_impl``; the dict # also caches any tensor type the user explicitly queries later self._bindings: dict[int, Any] = {} diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py index b83c22467ddf..7a7ab41d364f 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py @@ -20,6 +20,7 @@ from isaaclab.assets.rigid_object.base_rigid_object import BaseRigidObject from isaaclab.assets.rigid_object.rigid_object_cfg import RigidObjectCfg +from isaaclab.cloner import queue_usd_replication from isaaclab.sim.utils.queries import get_all_matching_child_prims, resolve_matching_prims_from_source from isaaclab.utils.string import resolve_matching_names from isaaclab.utils.wrench_composer import WrenchComposer @@ -27,6 +28,7 @@ from isaaclab_ovphysx import tensor_types as TT from isaaclab_ovphysx.assets import kernels as shared_kernels from isaaclab_ovphysx.assets.kernels import _body_wrench_to_world +from isaaclab_ovphysx.cloner import queue_ovphysx_replication from isaaclab_ovphysx.physics import OvPhysxManager from .rigid_object_data import RigidObjectData @@ -62,6 +64,8 @@ def __init__(self, cfg: RigidObjectCfg): cfg: A configuration instance. """ super().__init__(cfg) + queue_usd_replication(cfg) + queue_ovphysx_replication(cfg) # Bindings are created lazily (on first access) to avoid allocating # handles for tensor types the user never queries. self._bindings: dict[int, Any] = {} diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py index e9ce0ee45fc3..9aea366ad4ee 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py @@ -18,12 +18,14 @@ import isaaclab.sim as sim_utils from isaaclab.assets.rigid_object_collection.base_rigid_object_collection import BaseRigidObjectCollection +from isaaclab.cloner import queue_usd_replication from isaaclab.utils.string import resolve_matching_names from isaaclab.utils.wrench_composer import WrenchComposer from isaaclab_ovphysx import tensor_types as TT from isaaclab_ovphysx.assets import kernels as shared_kernels from isaaclab_ovphysx.assets.kernels import _body_wrench_to_world, resolve_view_ids +from isaaclab_ovphysx.cloner import queue_ovphysx_replication from isaaclab_ovphysx.physics import OvPhysxManager from .rigid_object_collection_data import RigidObjectCollectionData @@ -74,7 +76,7 @@ def __init__(self, cfg: RigidObjectCollectionCfg): # flag for whether the asset is initialized self._is_initialized = False # spawn the rigid objects - for rigid_body_cfg in self.cfg.rigid_objects.values(): + for rigid_body_name, rigid_body_cfg in self.cfg.rigid_objects.items(): # spawn the asset if rigid_body_cfg.spawn is not None: rigid_body_cfg.spawn.func( @@ -87,6 +89,8 @@ def __init__(self, cfg: RigidObjectCollectionCfg): matching_prims = sim_utils.find_matching_prims(rigid_body_cfg.prim_path) if len(matching_prims) == 0: raise RuntimeError(f"Could not find prim with path {rigid_body_cfg.prim_path}.") + queue_usd_replication(cfg.rigid_objects[rigid_body_name]) + queue_ovphysx_replication(cfg.rigid_objects[rigid_body_name]) # stores object names self._body_names_list: list[str] = [] # one fused TensorBinding per tensor type, populated in _initialize_impl diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/__init__.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/__init__.py index 3b9a12007792..34358e402794 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/__init__.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/__init__.py @@ -3,6 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -from .ovphysx_replicate import ovphysx_replicate +from .replicate import OvPhysxReplicateContext, ovphysx_replicate, queue_ovphysx_replication -__all__ = ["ovphysx_replicate"] +__all__ = ["OvPhysxReplicateContext", "ovphysx_replicate", "queue_ovphysx_replication"] diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py deleted file mode 100644 index d89a45280a50..000000000000 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/ovphysx_replicate.py +++ /dev/null @@ -1,105 +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 - -"""OvPhysX replication hook for IsaacLab's cloning pipeline. - -Called from the scene cloning path in place of immediate PhysX or Newton -replication. Unlike those replicators, ovphysx.PhysX does not exist yet at -this point in the scene setup — it is created lazily on the first -:meth:`~isaaclab_ovphysx.physics.OvPhysxManager.reset` call. - -This function records a *pending clone* on :class:`OvPhysxManager`. When -:meth:`~isaaclab_ovphysx.physics.OvPhysxManager._warmup_and_load` eventually -creates the ``PhysX`` instance and loads the USD stage (which contains only -``env_0`` physics — env_1..N are empty Xform containers), it replays every -pending clone via ``physx.clone(source, targets)`` to create the remaining -environments entirely inside the physics runtime without touching USD. -""" - -from __future__ import annotations - -from collections.abc import Sequence - -import torch - -from pxr import Usd - - -def ovphysx_replicate( - stage: Usd.Stage, - sources: Sequence[str], - destinations: Sequence[str], - env_ids: torch.Tensor, - mapping: torch.Tensor, - positions: torch.Tensor | None = None, - quaternions: torch.Tensor | None = None, - device: str = "cpu", -) -> None: - """Record a physics clone for later execution by OvPhysxManager. - - Translates the generic IsaacLab source/destination/mapping representation - into ``(source_path, [target_paths])`` pairs and registers them on - :class:`~isaaclab_ovphysx.physics.OvPhysxManager`. The actual - ``physx.clone()`` calls happen in ``_warmup_and_load()`` after the USD - stage has been loaded. - - The ``positions`` parameter contains the 2-D grid world positions for all - environments. They are forwarded to the C++ clone plugin so that the - parent Xform prim for each clone (e.g. ``/World/envs/env_N``) is placed at - the correct grid location in Fabric. The exported USD stage only contains - ``env_0``; without explicit positions all clone parents would be created at - the origin, causing all articulations to pile up and the GPU solver to - diverge on the first warmup step. - - Args: - stage: USD stage (not modified by this function). - sources: Source prim paths (one per prototype). - destinations: Destination path templates with ``"{}"`` for env index. - env_ids: Environment indices tensor. - mapping: ``(num_sources, num_envs)`` bool tensor; True selects which - environments receive each source. - positions: World (x, y, z) positions for every environment, shape - ``[num_envs, 3]``. Used to place clone parent Xform prims in - Fabric at correct grid locations. - quaternions: Ignored — orientations are set at first reset. - device: Torch device (unused; kept for API compatibility). - """ - # Deferred import to avoid circular dependency at module load time. - from isaaclab_ovphysx.physics.ovphysx_manager import OvPhysxManager - - for i, src in enumerate(sources): - active_env_ids = env_ids[mapping[i]].tolist() - - # Exclude the source environment from its own target list. - # physx.clone() is only needed for *other* envs; the source env_0 is - # already loaded from USD. We detect self by matching the source path - # against the destination template. - pre, _, suf = destinations[i].partition("{}") - self_env_id: int | None = None - candidate = src.removeprefix(pre).removesuffix(suf) - if candidate.isdigit(): - self_env_id = int(candidate) - - # Build parallel (targets, parent_positions) lists for non-self envs. - # parent_positions[j] is the world (x,y,z) for the parent Xform of - # targets[j] (e.g. /World/envs/env_N). These positions are passed to - # the C++ clone plugin so that env_N Xform prims — absent from the - # exported USD stage — are created at the correct 2-D grid location - # rather than the origin. Without this, all clones pile up at env_0's - # position during the warmup physics step and the GPU solver diverges. - targets: list[str] = [] - parent_positions: list[tuple[float, float, float]] = [] - for e in active_env_ids: - if e == self_env_id: - continue - targets.append(destinations[i].format(e)) - if positions is not None and e < len(positions): - pos = positions[e] - parent_positions.append((float(pos[0]), float(pos[1]), float(pos[2]))) - else: - parent_positions.append((0.0, 0.0, 0.0)) - - if targets: - OvPhysxManager.register_clone(src, targets, parent_positions) diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/replicate.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/replicate.py new file mode 100644 index 000000000000..d1fbe451ea8f --- /dev/null +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/cloner/replicate.py @@ -0,0 +1,185 @@ +# 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 + +"""OvPhysX replication hook for IsaacLab's cloning pipeline. + +Called from the scene cloning path in place of immediate PhysX or Newton +replication. Unlike those replicators, ovphysx.PhysX does not exist yet at +this point in the scene setup — it is created lazily on the first +:meth:`~isaaclab_ovphysx.physics.OvPhysxManager.reset` call. + +This function records a *pending clone* on :class:`OvPhysxManager`. When +:meth:`~isaaclab_ovphysx.physics.OvPhysxManager._warmup_and_load` eventually +creates the ``PhysX`` instance and loads the USD stage (which contains only +``env_0`` physics — env_1..N are empty Xform containers), it replays every +pending clone via ``physx.clone(source, targets)`` to create the remaining +environments entirely inside the physics runtime without touching USD. +""" + +from __future__ import annotations + +from collections.abc import Sequence +from typing import Any + +import torch + +from pxr import Sdf, Usd + +from isaaclab.cloner.replicate_session import REPLICATION_QUEUE + + +def _select_env_ids(env_ids: torch.Tensor, mapping: torch.Tensor, row: int) -> torch.Tensor: + """Return the environment ids selected by a replication row.""" + row_mask = mapping[row] + if row_mask.dtype != torch.bool: + row_mask = row_mask.to(dtype=torch.bool) + return env_ids[row_mask] + + +class OvPhysxReplicateContext: + """Queue and run OvPhysX clone operations for one stage.""" + + def __init__(self, stage: Usd.Stage): + """Initialize the context. + + Args: + stage: USD stage associated with the pending clone operations. + """ + self.stage = stage + physics_scene_prim = self.stage.GetPrimAtPath("/physicsScene") + if physics_scene_prim.IsValid(): + physics_scene_prim.CreateAttribute("physxScene:envIdInBoundsBitCount", Sdf.ValueTypeNames.Int).Set(4) + self._queue: list[tuple[str, list[str], list[tuple[float, float, float]]]] = [] + + def queue( + self, source: str, targets: Sequence[str], parent_positions: Sequence[tuple[float, float, float]] + ) -> None: + """Queue one pending OvPhysX clone operation. + + Args: + source: Source prim path. + targets: Destination prim paths. + parent_positions: Parent Xform positions [m] for each destination. + """ + self._queue.append((source, list(targets), list(parent_positions))) + + def queue_mapping( + self, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mapping: torch.Tensor, + *, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + ) -> None: + """Queue clone operations from the current flat clone mapping. + + Args: + sources: Source prim paths. + destinations: Destination path templates with ``"{}"`` for env id. + env_ids: Environment indices. + mapping: Bool/int mask selecting envs per source. + positions: Optional per-environment world positions [m]. + quaternions: Optional per-environment orientations, unused by OvPhysX. + """ + del quaternions + + for i, src in enumerate(sources): + active_env_ids = _select_env_ids(env_ids, mapping, i).tolist() + + pre, _, suf = destinations[i].partition("{}") + self_env_id: int | None = None + candidate = src.removeprefix(pre).removesuffix(suf) + if candidate.isdigit(): + self_env_id = int(candidate) + + targets: list[str] = [] + parent_positions: list[tuple[float, float, float]] = [] + for env_id in active_env_ids: + env_id = int(env_id) + if env_id == self_env_id: + continue + targets.append(destinations[i].format(env_id)) + if positions is not None and env_id < len(positions): + pos = positions[env_id] + parent_positions.append((float(pos[0]), float(pos[1]), float(pos[2]))) + else: + parent_positions.append((0.0, 0.0, 0.0)) + + if targets: + self.queue(src, targets, parent_positions) + + def replicate(self) -> None: + """Publish all queued clones to :class:`OvPhysxManager`.""" + from isaaclab_ovphysx.physics.ovphysx_manager import OvPhysxManager + + for source, targets, parent_positions in self._queue: + OvPhysxManager.register_clone(source, targets, parent_positions) + self._queue.clear() + + +def queue_ovphysx_replication(cfg: Any) -> None: + """Register ``cfg`` for OvPhysX replication when :func:`~isaaclab.cloner.replicate` next runs. + + Appends ``(cfg, OvPhysxReplicateContext)`` to + :data:`~isaaclab.cloner.REPLICATION_QUEUE`. The actual row resolution and dispatch + happen inside :func:`~isaaclab.cloner.replicate`, so this helper is safe to call from + any asset constructor — no active session is required. + """ + REPLICATION_QUEUE.append((cfg, OvPhysxReplicateContext)) + + +def ovphysx_replicate( + stage: Usd.Stage, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mapping: torch.Tensor, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + device: str = "cpu", +) -> None: + """Record a physics clone for later execution by OvPhysxManager. + + Translates the generic IsaacLab source/destination/mapping representation + into ``(source_path, [target_paths])`` pairs and registers them on + :class:`~isaaclab_ovphysx.physics.OvPhysxManager`. The actual + ``physx.clone()`` calls happen in ``_warmup_and_load()`` after the USD + stage has been loaded. + + The ``positions`` parameter contains the 2-D grid world positions for all + environments. They are forwarded to the C++ clone plugin so that the + parent Xform prim for each clone (e.g. ``/World/envs/env_N``) is placed at + the correct grid location in Fabric. The exported USD stage only contains + ``env_0``; without explicit positions all clone parents would be created at + the origin, causing all articulations to pile up and the GPU solver to + diverge on the first warmup step. + + Args: + stage: USD stage (not modified by this function). + sources: Source prim paths (one per prototype). + destinations: Destination path templates with ``"{}"`` for env index. + env_ids: Environment indices tensor. + mapping: ``(num_sources, num_envs)`` bool tensor; True selects which + environments receive each source. + positions: World (x, y, z) positions [m] for every environment, shape + ``[num_envs, 3]``. Used to place clone parent Xform prims in + Fabric at correct grid locations. + quaternions: Ignored — orientations are set at first reset. + device: Torch device (unused; kept for API compatibility). + """ + del device + + ctx = OvPhysxReplicateContext(stage) + ctx.queue_mapping( + sources, + destinations, + env_ids, + mapping, + positions=positions, + quaternions=quaternions, + ) + ctx.replicate() diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py index 8f7e1e576f17..8fc63190a795 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py @@ -211,8 +211,8 @@ class OvPhysxManager(PhysicsManager): # :meth:`_release_physx`); we mirror it here so a clear Python error is raised # if a later :class:`~isaaclab.sim.SimulationContext` requests a different device. _locked_device: ClassVar[str | None] = None - # Pending (source, targets, parent_positions) triples registered by - # ovphysx_replicate() before the PhysX instance exists. Replayed via + # Pending (source, targets, parent_positions) triples queued by + # queue_ovphysx_replication() before the PhysX instance exists. Replayed via # physx.clone() in _warmup_and_load(). # parent_positions is a list of (x, y, z) tuples — one per target. _pending_clones: ClassVar[list[tuple[str, list[str], list[tuple[float, float, float]]]]] = [] @@ -572,10 +572,9 @@ def _warmup_and_load(cls) -> None: # Xform containers. physx.clone() creates the remaining environments # in the physics runtime without modifying the USD file. if cls._pending_clones: - # ovphysx_replicate() only registers pending clones when clone_usd=False, - # meaning the USD contains only env_0 physics and physx.clone() is required - # to populate env_1..N in the physics runtime. Execute unconditionally — - # no USD content heuristic is needed. + # The cfg-level OvPhysX replicator registers pending clones for physics + # regardless of whether USD copies were also queued for rendering. Execute + # unconditionally — no USD content heuristic is needed. for source, targets, parent_positions in cls._pending_clones: logger.info( "OvPhysxManager: cloning %s -> %d targets (%s ... %s)", diff --git a/source/isaaclab_physx/changelog.d/replication-session-redesign.skip b/source/isaaclab_physx/changelog.d/replication-session-redesign.skip new file mode 100644 index 000000000000..8b9f8ee958aa --- /dev/null +++ b/source/isaaclab_physx/changelog.d/replication-session-redesign.skip @@ -0,0 +1,5 @@ +Internal refactor: ``queue_physx_replication`` now appends ``(cfg, +PhysxReplicateContext)`` to :data:`isaaclab.cloner.REPLICATION_QUEUE` instead of +reaching into the now-removed module-level replication session. No user-visible +behavior change — :func:`~isaaclab.cloner.replicate` still drives PhysX replication +via :class:`PhysxReplicateContext` exactly as before. diff --git a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py index 933ab5078201..e2e442f02539 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/articulation/articulation.py @@ -23,6 +23,7 @@ from isaaclab.actuators import ActuatorBase, ActuatorBaseCfg, ImplicitActuator from isaaclab.assets.articulation.base_articulation import BaseArticulation +from isaaclab.cloner import queue_usd_replication from isaaclab.sim.utils.queries import ( find_first_matching_prim, get_all_matching_child_prims, @@ -38,6 +39,7 @@ from isaaclab_physx.assets import kernels as shared_kernels from isaaclab_physx.assets.articulation import kernels as articulation_kernels +from isaaclab_physx.cloner import queue_physx_replication from isaaclab_physx.physics import PhysxManager as SimulationManager from .articulation_data import ArticulationData @@ -124,6 +126,8 @@ def __init__(self, cfg: ArticulationCfg): from isaaclab.sim import SimulationContext # noqa: PLC0415 super().__init__(cfg) + queue_usd_replication(cfg) + queue_physx_replication(cfg) sim_ctx = SimulationContext.instance() self._sim_cfg = sim_ctx.cfg if sim_ctx is not None else None diff --git a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py index 4b77eac60997..ef5fb2038d57 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object.py @@ -19,9 +19,11 @@ import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils from isaaclab.assets.asset_base import AssetBase +from isaaclab.cloner import queue_usd_replication from isaaclab.markers import VisualizationMarkers from isaaclab.utils.warp import ProxyArray +from isaaclab_physx.cloner import queue_physx_replication from isaaclab_physx.physics import PhysxManager as SimulationManager from .deformable_object_data import DeformableObjectData @@ -80,6 +82,8 @@ def __init__(self, cfg: DeformableObjectCfg): cfg: A configuration instance. """ super().__init__(cfg) + queue_usd_replication(cfg) + queue_physx_replication(cfg) # Register custom vec6f type for nodal state validation. self._DTYPE_TO_TORCH_TRAILING_DIMS = {**self._DTYPE_TO_TORCH_TRAILING_DIMS, vec6f: (6,)} # initialize deformable type to None, should be set to either surface or volume on initialization diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py index 793af2cf4b9c..51c70e595440 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object/rigid_object.py @@ -17,10 +17,12 @@ import isaaclab.utils.string as string_utils from isaaclab.assets.rigid_object.base_rigid_object import BaseRigidObject +from isaaclab.cloner import queue_usd_replication from isaaclab.sim.utils.queries import get_all_matching_child_prims, resolve_matching_prims_from_source from isaaclab.utils.wrench_composer import WrenchComposer from isaaclab_physx.assets import kernels as shared_kernels +from isaaclab_physx.cloner import queue_physx_replication from isaaclab_physx.physics import PhysxManager as SimulationManager from .rigid_object_data import RigidObjectData @@ -65,6 +67,8 @@ def __init__(self, cfg: RigidObjectCfg): cfg: A configuration instance. """ super().__init__(cfg) + queue_usd_replication(cfg) + queue_physx_replication(cfg) """ Properties diff --git a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py index 37c9e6616608..8e0a33e4582a 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/rigid_object_collection/rigid_object_collection.py @@ -21,9 +21,11 @@ import isaaclab.sim as sim_utils import isaaclab.utils.string as string_utils from isaaclab.assets.rigid_object_collection.base_rigid_object_collection import BaseRigidObjectCollection +from isaaclab.cloner import queue_usd_replication from isaaclab.utils.wrench_composer import WrenchComposer from isaaclab_physx.assets import kernels as shared_kernels +from isaaclab_physx.cloner import queue_physx_replication from isaaclab_physx.physics import PhysxManager as SimulationManager from .kernels import resolve_view_ids @@ -78,7 +80,7 @@ def __init__(self, cfg: RigidObjectCollectionCfg): # flag for whether the asset is initialized self._is_initialized = False # spawn the rigid objects - for rigid_body_cfg in self.cfg.rigid_objects.values(): + for rigid_body_name, rigid_body_cfg in self.cfg.rigid_objects.items(): # spawn the asset if rigid_body_cfg.spawn is not None: spawn_path = rigid_body_cfg.spawn.spawn_path or rigid_body_cfg.prim_path @@ -92,6 +94,8 @@ def __init__(self, cfg: RigidObjectCollectionCfg): matching_prims = sim_utils.find_matching_prims(rigid_body_cfg.prim_path) if len(matching_prims) == 0: raise RuntimeError(f"Could not find prim with path {rigid_body_cfg.prim_path}.") + queue_usd_replication(cfg.rigid_objects[rigid_body_name]) + queue_physx_replication(cfg.rigid_objects[rigid_body_name]) # stores object names self._body_names_list = [] diff --git a/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py b/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py index ea7adbf6c6d9..7a9f61df07aa 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper.py @@ -17,8 +17,11 @@ import isaaclab.sim as sim_utils from isaaclab.assets import AssetBase +from isaaclab.cloner import queue_usd_replication from isaaclab.utils.version import get_isaac_sim_version, has_kit +from isaaclab_physx.cloner import queue_physx_replication + if TYPE_CHECKING: from isaacsim.robot.surface_gripper import GripperView @@ -98,6 +101,9 @@ def __init__(self, cfg: SurfaceGripperCfg): self._is_initialized = False self._debug_vis_handle = None + queue_usd_replication(cfg) + queue_physx_replication(cfg) + # register various callback functions self._register_callbacks() diff --git a/source/isaaclab_physx/isaaclab_physx/cloner/__init__.pyi b/source/isaaclab_physx/isaaclab_physx/cloner/__init__.pyi index ecc5b6e3923e..d865b4f56e80 100644 --- a/source/isaaclab_physx/isaaclab_physx/cloner/__init__.pyi +++ b/source/isaaclab_physx/isaaclab_physx/cloner/__init__.pyi @@ -4,7 +4,9 @@ # SPDX-License-Identifier: BSD-3-Clause __all__ = [ + "PhysxReplicateContext", "physx_replicate", + "queue_physx_replication", ] -from .physx_replicate import physx_replicate +from .replicate import PhysxReplicateContext, physx_replicate, queue_physx_replication diff --git a/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py b/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py deleted file mode 100644 index dcc5cc6d9677..000000000000 --- a/source/isaaclab_physx/isaaclab_physx/cloner/physx_replicate.py +++ /dev/null @@ -1,113 +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 - -from __future__ import annotations - -from collections.abc import Sequence - -import torch - -from omni.physx import get_physx_replicator_interface -from pxr import Usd, UsdUtils - - -def physx_replicate( - stage: Usd.Stage, - sources: Sequence[str], # e.g. ["/World/Template/A", "/World/Template/B"] - destinations: Sequence[str], # e.g. ["/World/envs/env_{}/Robot", "/World/envs/env_{}/Object"] - env_ids: torch.Tensor, # env_ids - mapping: torch.Tensor, # (num_sources, num_envs) bool; True -> place sources[i] into world=j - positions: torch.Tensor | None = None, - quaternions: torch.Tensor | None = None, - use_fabric: bool = False, - device: str = "cpu", - exclude_self_replication: bool = True, -) -> None: - """Replicate prims via PhysX replicator with per-row mapping. - - Builds per-source destination lists from ``mapping`` and calls PhysX ``replicate``. - Rows covering all environments use ``useEnvIds=True``; partial rows use ``False``. - The replicator is registered for the call and then unregistered. - - ``attach_fn`` excludes ``/World/template`` and ``/World/envs`` so that PhysX does - not independently parse prims that the replicator will handle. The source prim - receives its physics body as a side-effect of ``rep.replicate()`` (which always - parses the source internally), so every source must appear in at least one - ``replicate`` call. - - When ``exclude_self_replication`` is True (default), each source environment is - removed from its own replication targets so the replicator only creates bodies at - non-self destinations. If removing self would leave the world list empty (i.e. the - source maps only to its own environment), self is kept so that ``rep.replicate()`` - is still called and the source prim gets its physics body. - - Args: - stage: USD stage. - sources: Source prim paths (``S``). - destinations: Destination templates (``S``) with ``"{}"`` for env index. - env_ids: Environment indices (``[E]``). - mapping: Bool/int mask (``[S, E]``) selecting envs per source. - positions: Optional positions (unused, for API compatibility). - quaternions: Optional orientations (unused, for API compatibility). - use_fabric: Use Fabric for replication. - device: Torch device for determining replication mode. - exclude_self_replication: If True, skip replicating a source prim onto itself - when the source also maps to other environments. Default is True. - Self-only sources always keep self so that ``rep.replicate()`` fires. - - Returns: - None - """ - # Note: positions and quaternions are unused by PhysX replicator - # They are included for API compatibility with other backends (e.g., Newton) - del positions, quaternions - - stage_id = UsdUtils.StageCache.Get().Insert(stage).ToLongInt() - current_worlds: list[int] = [] - current_template: str = "" - num_envs = mapping.size(1) - - if num_envs > 1: - # Pre-compute effective world lists after self-exclusion. - # Self is only removed when the source also maps to other environments; - # if it is the sole destination we must keep it so that rep.replicate() - # is still called (the source gets its physics body from that call). - effective_worlds: list[list[int]] = [] - for i, src in enumerate(sources): - worlds = env_ids[mapping[i]].tolist() - if exclude_self_replication: - pre, _, suf = destinations[i].partition("{}") - self_id = src.removeprefix(pre).removesuffix(suf) - if self_id.isdigit(): - filtered = [w for w in worlds if w != int(self_id)] - worlds = filtered if filtered else worlds - effective_worlds.append(worlds) - - def attach_fn(_stage_id: int): - return ["/World/template", "/World/envs"] - - def rename_fn(_replicate_path: str, i: int): - return current_template.format(current_worlds[i]) - - def attach_end_fn(_stage_id: int): - nonlocal current_template - rep = get_physx_replicator_interface() - for i, src in enumerate(sources): - current_template = destinations[i] - current_worlds[:] = effective_worlds[i] - if not current_worlds: - continue - rep.replicate( - _stage_id, - src, - len(current_worlds), - # TODO: envIds needs to support heterogeneous setup. for now, we rely on USD collision filtering - useEnvIds=False, # (len(current_worlds) == num_envs - 1) and device != "cpu", - useFabricForReplication=use_fabric, - ) - # unregister only AFTER all replicate() calls completed - rep.unregister_replicator(_stage_id) - - get_physx_replicator_interface().register_replicator(stage_id, attach_fn, attach_end_fn, rename_fn) diff --git a/source/isaaclab_physx/isaaclab_physx/cloner/replicate.py b/source/isaaclab_physx/isaaclab_physx/cloner/replicate.py new file mode 100644 index 000000000000..9fa00e8c3b75 --- /dev/null +++ b/source/isaaclab_physx/isaaclab_physx/cloner/replicate.py @@ -0,0 +1,196 @@ +# 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 + +from __future__ import annotations + +from collections.abc import Sequence +from typing import Any + +import torch + +from omni.physx import get_physx_replicator_interface +from pxr import Sdf, Usd, UsdUtils + +from isaaclab.cloner.replicate_session import REPLICATION_QUEUE + + +def _select_env_ids(env_ids: torch.Tensor, mapping: torch.Tensor, row: int) -> torch.Tensor: + """Return the environment ids selected by a replication row.""" + row_mask = mapping[row] + if row_mask.dtype != torch.bool: + row_mask = row_mask.to(dtype=torch.bool) + return env_ids[row_mask] + + +class PhysxReplicateContext: + """Queue and run PhysX replication work for one stage.""" + + def __init__(self, stage: Usd.Stage): + """Initialize the context. + + Args: + stage: USD stage to register with the PhysX replicator. + """ + self.stage = stage + self._stage_id = UsdUtils.StageCache.Get().Insert(stage).ToLongInt() + physics_scene_prim = self.stage.GetPrimAtPath("/physicsScene") + if physics_scene_prim.IsValid(): + physics_scene_prim.CreateAttribute("physxScene:envIdInBoundsBitCount", Sdf.ValueTypeNames.Int).Set(4) + self._queue: list[tuple[str, str, tuple[int, ...]]] = [] + + def queue(self, source: str, destination: str, target_envs: Sequence[int]) -> None: + """Queue one PhysX source row for replication. + + Args: + source: Source prim path. + destination: Destination path template with ``"{}"`` for env id. + target_envs: Environment ids selected for this source row. + """ + self._queue.append((source, destination, tuple(int(env_id) for env_id in target_envs))) + + def queue_mapping( + self, + sources: Sequence[str], + destinations: Sequence[str], + env_ids: torch.Tensor, + mapping: torch.Tensor, + *, + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + exclude_self_replication: bool = True, + ) -> None: + """Queue replication rows from the current flat clone mapping. + + Args: + sources: Source prim paths. + destinations: Destination path templates with ``"{}"`` for env id. + env_ids: Environment indices. + mapping: Bool/int mask selecting envs per source. + positions: Optional per-environment world positions [m], unused by PhysX. + quaternions: Optional per-environment orientations, unused by PhysX. + exclude_self_replication: Whether to skip replicating a source prim onto itself + when it also maps to other environments. + """ + del positions, quaternions + + if mapping.size(1) <= 1: + return + + for i, src in enumerate(sources): + worlds = _select_env_ids(env_ids, mapping, i).tolist() + if exclude_self_replication: + pre, _, suf = destinations[i].partition("{}") + self_id = src.removeprefix(pre).removesuffix(suf) + if self_id.isdigit(): + filtered = [w for w in worlds if w != int(self_id)] + worlds = filtered if filtered else worlds + self.queue(src, destinations[i], worlds) + + def replicate(self) -> None: + """Register the PhysX replicator and run queued rows from ``attach_end_fn``.""" + if not self._queue: + return + + physx_queue = tuple(self._queue) + current_worlds: list[int] = [] + current_template: str = "" + + def attach_fn(_stage_id: int): + return ["/World/template", "/World/envs"] + + def rename_fn(_replicate_path: str, i: int): + return current_template.format(current_worlds[i]) + + def attach_end_fn(_stage_id: int): + nonlocal current_template + rep = get_physx_replicator_interface() + for src, destination, target_envs in physx_queue: + current_template = destination + current_worlds[:] = target_envs + if not current_worlds: + continue + rep.replicate( + _stage_id, + src, + len(current_worlds), + # TODO: envIds needs to support heterogeneous setup. for now, we rely on USD collision filtering + useEnvIds=False, + useFabricForReplication=False, + ) + rep.unregister_replicator(_stage_id) + + get_physx_replicator_interface().register_replicator(self._stage_id, attach_fn, attach_end_fn, rename_fn) + self._queue.clear() + + +def queue_physx_replication(cfg: Any) -> None: + """Register ``cfg`` for PhysX replication when :func:`~isaaclab.cloner.replicate` next runs. + + Appends ``(cfg, PhysxReplicateContext)`` to + :data:`~isaaclab.cloner.REPLICATION_QUEUE`. The actual row resolution and dispatch + happen inside :func:`~isaaclab.cloner.replicate`, so this helper is safe to call from + any asset constructor — no active session is required. + """ + REPLICATION_QUEUE.append((cfg, PhysxReplicateContext)) + + +def physx_replicate( + stage: Usd.Stage, + sources: Sequence[str], # e.g. ["/World/Template/A", "/World/Template/B"] + destinations: Sequence[str], # e.g. ["/World/envs/env_{}/Robot", "/World/envs/env_{}/Object"] + env_ids: torch.Tensor, # env_ids + mapping: torch.Tensor, # (num_sources, num_envs) bool; True -> place sources[i] into world=j + positions: torch.Tensor | None = None, + quaternions: torch.Tensor | None = None, + device: str = "cpu", + exclude_self_replication: bool = True, +) -> None: + """Replicate prims via PhysX replicator with per-row mapping. + + Builds per-source destination lists from ``mapping`` and calls PhysX ``replicate``. + The replicator is registered for the call and then unregistered. Heterogeneous + rows currently use ``useEnvIds=False`` and rely on USD collision filtering. + + ``attach_fn`` excludes ``/World/template`` and ``/World/envs`` so that PhysX does + not independently parse prims that the replicator will handle. The source prim + receives its physics body as a side-effect of ``rep.replicate()`` (which always + parses the source internally), so every source must appear in at least one + ``replicate`` call. + + When ``exclude_self_replication`` is True (default), each source environment is + removed from its own replication targets so the replicator only creates bodies at + non-self destinations. If removing self would leave the world list empty (i.e. the + source maps only to its own environment), self is kept so that ``rep.replicate()`` + is still called and the source prim gets its physics body. + + Args: + stage: USD stage. + sources: Source prim paths (``S``). + destinations: Destination templates (``S``) with ``"{}"`` for env index. + env_ids: Environment indices (``[E]``). + mapping: Bool/int mask (``[S, E]``) selecting envs per source. + positions: Optional positions (unused, for API compatibility). + quaternions: Optional orientations (unused, for API compatibility). + device: Unused legacy argument retained for API compatibility. + exclude_self_replication: If True, skip replicating a source prim onto itself + when the source also maps to other environments. Default is True. + Self-only sources always keep self so that ``rep.replicate()`` fires. + + Returns: + None + """ + del device + + ctx = PhysxReplicateContext(stage) + ctx.queue_mapping( + sources, + destinations, + env_ids, + mapping, + positions=positions, + quaternions=quaternions, + exclude_self_replication=exclude_self_replication, + ) + ctx.replicate() diff --git a/source/isaaclab_physx/test/sim/test_cloner.py b/source/isaaclab_physx/test/sim/test_cloner.py index 882963076bb1..68b7a36e60be 100644 --- a/source/isaaclab_physx/test/sim/test_cloner.py +++ b/source/isaaclab_physx/test/sim/test_cloner.py @@ -17,18 +17,38 @@ import pytest import torch import warp as wp -from isaaclab_physx.cloner import physx_replicate +from isaaclab_physx.cloner import PhysxReplicateContext, physx_replicate import isaaclab.sim as sim_utils from isaaclab.cloner import ( _fabric_notices, disabled_fabric_change_notifies, - make_clone_plan, sequential, usd_replicate, ) from isaaclab.sim import build_simulation_context + +def _make_flat_clone_plan(num_variants: int, num_clones: int, destination: str, device: str): + """Build a flat (sources, destinations, clone_mask) tuple for tests using sequential mapping. + + The PhysX test_cloner tests intentionally bypass cfg-driven planning and exercise + physx_replicate / usd_replicate against a hand-built per-variant mask. This helper + captures the small amount of flat-plan logic the tests need without re-introducing + the legacy ``make_clone_plan(sources, destinations, num_clones, ...)`` signature. + """ + chosen = sequential( + torch.arange(num_variants, dtype=torch.long, device=device).unsqueeze(1), + num_clones, + device, + ).view(-1) + mask = torch.zeros((num_variants, num_clones), dtype=torch.bool, device=device) + mask[chosen, torch.arange(num_clones, device=device)] = True + sources = tuple(destination.format(i) for i in range(num_variants)) + destinations = tuple([destination] * num_variants) + return sources, destinations, mask + + wp.init() pytestmark = pytest.mark.isaacsim_ci @@ -107,6 +127,29 @@ def _fake_register(_stage_id, attach_fn, attach_end_fn, rename_fn): return mock_rep, replicate_calls, attach_excluded +def test_physx_replicate_context_queue_and_replicate(sim): + """PhysxReplicateContext queues mapping rows and replicates them through attach_end_fn.""" + from unittest.mock import patch + + stage = sim_utils.get_current_stage() + sim_utils.create_prim("/World/envs", "Xform") + for i in range(3): + sim_utils.create_prim(f"/World/envs/env_{i}", "Xform") + + mock_rep, replicate_calls = _make_mock_physx_rep() + with patch("isaaclab_physx.cloner.replicate.get_physx_replicator_interface", return_value=mock_rep): + ctx = PhysxReplicateContext(stage) + ctx.queue_mapping( + sources=["/World/envs/env_0/Object"], + destinations=["/World/envs/env_{}/Object"], + env_ids=torch.arange(3, dtype=torch.long), + mapping=torch.ones((1, 3), dtype=torch.bool), + ) + ctx.replicate() + + assert replicate_calls == [2] + + @pytest.mark.parametrize( "num_envs,src,expected_worlds", [ @@ -135,7 +178,7 @@ def test_physx_replicate_world_counts(sim, num_envs, src, expected_worlds): sim_utils.create_prim(f"/World/envs/env_{i}", "Xform") mock_rep, replicate_calls = _make_mock_physx_rep() - with patch("isaaclab_physx.cloner.physx_replicate.get_physx_replicator_interface", return_value=mock_rep): + with patch("isaaclab_physx.cloner.replicate.get_physx_replicator_interface", return_value=mock_rep): physx_replicate( stage, sources=[src], @@ -217,7 +260,7 @@ def test_physx_replicate_heterogeneous_isolated_sources(sim, device): mapping[2, [7, 11]] = True mock_rep, replicate_calls, attach_excluded = _make_mock_physx_rep_detailed() - with patch("isaaclab_physx.cloner.physx_replicate.get_physx_replicator_interface", return_value=mock_rep): + with patch("isaaclab_physx.cloner.replicate.get_physx_replicator_interface", return_value=mock_rep): physx_replicate( stage, sources=["/World/envs/env_0/Object", "/World/envs/env_5/Object", "/World/envs/env_7/Object"], @@ -271,15 +314,13 @@ def test_direct_clone_plan_multi_asset(sim): mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) - sources, destinations, clone_mask = make_clone_plan( - [[f"/World/envs/env_{i}/Object" for i in range(len(cfg.assets_cfg))]], - ["/World/envs/env_{}/Object"], - num_clones, - sequential, - sim.cfg.device, + sources, destinations, clone_mask = _make_flat_clone_plan( + num_variants=len(cfg.assets_cfg), + num_clones=num_clones, + destination="/World/envs/env_{}/Object", + device=sim.cfg.device, ) - spawn_paths: list[str | None] = list(sources) - cfg.spawn_paths = spawn_paths + cfg.spawn_paths = list(sources) prim = cfg.func("/World/unused", cfg) assert prim.IsValid() @@ -315,16 +356,14 @@ def _run_colocation_collision_filter(sim, asset_cfg, expected_types, assert_coun sim_utils.create_prim(f"/World/envs/env_{i}", "Xform", translation=(0, 0, 0)) num_variants = len(asset_cfg.assets_cfg) if isinstance(asset_cfg, sim_utils.MultiAssetSpawnerCfg) else 1 - sources, destinations, clone_mask = make_clone_plan( - [[f"/World/envs/env_{i}/Object" for i in range(num_variants)]], - ["/World/envs/env_{}/Object"], - num_clones, - sequential, - sim.cfg.device, + sources, destinations, clone_mask = _make_flat_clone_plan( + num_variants=num_variants, + num_clones=num_clones, + destination="/World/envs/env_{}/Object", + device=sim.cfg.device, ) if isinstance(asset_cfg, sim_utils.MultiAssetSpawnerCfg): - spawn_paths: list[str | None] = list(sources) - asset_cfg.spawn_paths = spawn_paths + asset_cfg.spawn_paths = list(sources) prim = asset_cfg.func("/World/unused", asset_cfg) else: prim = asset_cfg.func(sources[0], asset_cfg) diff --git a/source/isaaclab_tasks/changelog.d/replication-session-redesign.skip b/source/isaaclab_tasks/changelog.d/replication-session-redesign.skip new file mode 100644 index 000000000000..c34b8831ae8d --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/replication-session-redesign.skip @@ -0,0 +1,4 @@ +Internal refactor: every direct env's ``_setup_scene`` now calls +``cloner.replicate(cloner.ClonePlan.from_env_0(...))`` after asset +construction in place of the prior ``with cloner.ReplicateSession():`` wrapper. +No user-visible behavior change. diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/anymal_c_direct/anymal_c_env.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/anymal_c_direct/anymal_c_env.py index 3c1c0aa0ef2f..f932022481e0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/anymal_c_direct/anymal_c_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/anymal_c_direct/anymal_c_env.py @@ -10,6 +10,7 @@ import warp as wp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sensors import ContactSensor, RayCaster @@ -72,8 +73,10 @@ def _setup_scene(self): self.cfg.terrain.num_envs = self.scene.cfg.num_envs self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing self._terrain = self.cfg.terrain.class_type(self.cfg.terrain) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env.py index e3037d67712d..10d9774f0361 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env.py @@ -10,6 +10,7 @@ import warp as wp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation, RigidObject from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -260,8 +261,11 @@ def _setup_scene(self): self._robot = Articulation(self.cfg.robot) self._fixed_asset = Articulation(self.cfg_task.fixed_asset) self._held_asset = RigidObject(self.cfg_task.held_asset) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) - self.scene.clone_environments(copy_from_source=False) self.scene.filter_collisions() self.scene.articulations["robot"] = self._robot diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env.py index 1982786f65a7..4d85fb4a2476 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env.py @@ -11,6 +11,7 @@ import warp as wp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation, RigidObject from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -185,8 +186,11 @@ def _setup_scene(self): # self._held_asset = Articulation(self.cfg_task.held_asset) # self._fixed_asset = RigidObject(self.cfg_task.fixed_asset) self._held_asset = RigidObject(self.cfg_task.held_asset) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) - self.scene.clone_environments(copy_from_source=False) self.scene.filter_collisions() self.scene.articulations["robot"] = self._robot diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env.py index c38fe071b161..4860be520982 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env.py @@ -9,6 +9,7 @@ import carb import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -97,8 +98,11 @@ def _setup_scene(self): if self.cfg_task.name == "gear_mesh": self._small_gear_asset = Articulation(self.cfg_task.small_gear_cfg) self._large_gear_asset = Articulation(self.cfg_task.large_gear_cfg) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) - self.scene.clone_environments(copy_from_source=False) if self.device == "cpu": # we need to explicitly filter collisions for CPU simulation self.scene.filter_collisions() diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/humanoid_amp/humanoid_amp_env.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/humanoid_amp/humanoid_amp_env.py index 7c0fe5036132..630ce90d032b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/humanoid_amp/humanoid_amp_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/humanoid_amp/humanoid_amp_env.py @@ -11,6 +11,7 @@ import warp as wp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -64,8 +65,10 @@ def _setup_scene(self): ), ), ) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=["/World/ground"]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/cart_double_pendulum/cart_double_pendulum_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/cart_double_pendulum/cart_double_pendulum_env.py index b1f66e34670f..d3861743ee59 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/cart_double_pendulum/cart_double_pendulum_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/cart_double_pendulum/cart_double_pendulum_env.py @@ -11,6 +11,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectMARLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -42,8 +43,10 @@ def _setup_scene(self): self.robot = Articulation(self.cfg.robot_cfg) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_camera_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_camera_env.py index 2d337c46f989..c0ccb26a4dda 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_camera_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_camera_env.py @@ -9,6 +9,7 @@ from typing import TYPE_CHECKING import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.sensors import Camera, save_images_to_file from isaaclab.utils.buffers import CircularBuffer @@ -82,9 +83,11 @@ def _setup_scene(self): """Setup the scene with the cartpole and camera (no ground plane, which obstructs the view).""" self.cartpole = Articulation(self.cfg.robot_cfg) self._tiled_camera = Camera(self.cfg.tiled_camera) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) if self.device == "cpu": # we need to explicitly filter collisions for CPU simulation self.scene.filter_collisions(global_prim_paths=[]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_env.py index 4a5b4e7375ee..b06701d04e53 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/cartpole/cartpole_direct_env.py @@ -12,6 +12,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -39,10 +40,10 @@ def __init__(self, cfg: CartpoleEnvCfg, render_mode: str | None = None, **kwargs def _setup_scene(self): self.cartpole = Articulation(self.cfg.robot_cfg) spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - - # clone and replicate - self.scene.clone_environments(copy_from_source=False) - + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env.py index 3f3d341c1aad..a6a1d028c0f9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env.py @@ -11,6 +11,7 @@ from pxr import UsdGeom import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sim.utils.stage import get_current_stage @@ -134,9 +135,11 @@ def _setup_scene(self): self.cfg.terrain.num_envs = self.scene.cfg.num_envs self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing self._terrain = self.cfg.terrain.class_type(self.cfg.terrain) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/inhand_manipulation/inhand_manipulation_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/inhand_manipulation/inhand_manipulation_env.py index 9f218b9d246b..a49a17e2c3ad 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/inhand_manipulation/inhand_manipulation_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/inhand_manipulation/inhand_manipulation_env.py @@ -13,6 +13,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation, RigidObject from isaaclab.envs import DirectRLEnv from isaaclab.markers import VisualizationMarkers @@ -101,8 +102,10 @@ def _setup_scene(self): self._joint_wrench_sensor = self._create_joint_wrench_sensor() # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate (no need to filter for this environment) - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # add articulation to scene - we must register to scene to randomize with EventManager self.scene.articulations["robot"] = self.hand self.scene.rigid_objects["object"] = self.object diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/locomotion/locomotion_direct_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/locomotion/locomotion_direct_env.py index 02be742eb018..121736ffc5d0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/locomotion/locomotion_direct_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/locomotion/locomotion_direct_env.py @@ -12,6 +12,7 @@ from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg from isaaclab.utils.math import ( @@ -116,8 +117,10 @@ def _setup_scene(self): self.cfg.terrain.num_envs = self.scene.cfg.num_envs self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing self.terrain = self.cfg.terrain.class_type(self.cfg.terrain) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_vision_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_vision_env.py index 92d45af9c40c..88c912ef631f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_vision_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_vision_env.py @@ -11,6 +11,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation, RigidObject from isaaclab.sensors import Camera from isaaclab.utils.math import quat_apply @@ -51,8 +52,10 @@ def _setup_scene(self): self.object: Articulation | RigidObject = self.cfg.object_cfg.class_type(self.cfg.object_cfg) self._joint_wrench_sensor = self._create_joint_wrench_sensor() self._tiled_camera = Camera(self.cfg.tiled_camera) - # clone and replicate (no need to filter for this environment) - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # add articulation to scene - we must register to scene to randomize with EventManager self.scene.articulations["robot"] = self.hand self.scene.rigid_objects["object"] = self.object diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env.py b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env.py index 66b9012d036b..9e1e56a3f5cc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env.py @@ -12,6 +12,7 @@ import torch import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation, RigidObject from isaaclab.envs import DirectMARLEnv from isaaclab.markers import VisualizationMarkers @@ -93,8 +94,10 @@ def _setup_scene(self): self.object = RigidObject(self.cfg.object_cfg) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate (no need to filter for this environment) - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # add articulation to scene - we must register to scene to randomize with EventManager self.scene.articulations["right_robot"] = self.right_hand self.scene.articulations["left_robot"] = self.left_hand diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/cartpole/cartpole_warp_env.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/cartpole/cartpole_warp_env.py index 25e9aa4bfd7d..14f776c95b0b 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/cartpole/cartpole_warp_env.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/cartpole/cartpole_warp_env.py @@ -12,6 +12,7 @@ from isaaclab_experimental.envs import DirectRLEnvWarp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -205,8 +206,10 @@ def _setup_scene(self) -> None: self.cartpole = Articulation(self.cfg.robot_cfg) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[]) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/inhand_manipulation/inhand_manipulation_warp_env.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/inhand_manipulation/inhand_manipulation_warp_env.py index d5bc6a2ad529..2082d470ff9b 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/inhand_manipulation/inhand_manipulation_warp_env.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/inhand_manipulation/inhand_manipulation_warp_env.py @@ -14,6 +14,7 @@ from isaaclab_experimental.envs import DirectRLEnvWarp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation # , RigidObject from isaaclab.markers import VisualizationMarkers from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -673,8 +674,10 @@ def _setup_scene(self): self.object = Articulation(self.cfg.object_cfg) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate (no need to filter for this environment) - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # add articulation to scene - we must register to scene to randomize with EventManager self.scene.articulations["robot"] = self.hand self.scene.articulations["object"] = self.object diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/locomotion/locomotion_env_warp.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/locomotion/locomotion_env_warp.py index d8d712a655e9..62400c4d48fe 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/locomotion/locomotion_env_warp.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/direct/locomotion/locomotion_env_warp.py @@ -9,6 +9,7 @@ from isaaclab_experimental.envs import DirectRLEnvWarp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnvCfg @@ -415,8 +416,10 @@ def _setup_scene(self) -> None: self.cfg.terrain.num_envs = self.scene.cfg.num_envs self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing self.terrain = self.cfg.terrain.class_type(self.cfg.terrain) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # add articulation to scene self.scene.articulations["robot"] = self.robot # add lights diff --git a/tools/template/templates/tasks/direct_multi-agent/env b/tools/template/templates/tasks/direct_multi-agent/env index eec2331722e8..0ca0ce4585ee 100644 --- a/tools/template/templates/tasks/direct_multi-agent/env +++ b/tools/template/templates/tasks/direct_multi-agent/env @@ -10,6 +10,7 @@ import torch from collections.abc import Sequence import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectMARLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -35,8 +36,11 @@ class {{ task.classname }}Env(DirectMARLEnv): self.robot = Articulation(self.cfg.robot_cfg) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + # build a homogeneous clone plan and replicate the env_0 layout to every env + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[]) diff --git a/tools/template/templates/tasks/direct_single-agent/env b/tools/template/templates/tasks/direct_single-agent/env index e6f47fd3366b..8f956c845b86 100644 --- a/tools/template/templates/tasks/direct_single-agent/env +++ b/tools/template/templates/tasks/direct_single-agent/env @@ -10,6 +10,7 @@ import torch from collections.abc import Sequence import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv from isaaclab.sim.spawners.from_files import GroundPlaneCfg, spawn_ground_plane @@ -34,8 +35,11 @@ class {{ task.classname }}Env(DirectRLEnv): self.robot = Articulation(self.cfg.robot_cfg) # add ground plane spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()) - # clone and replicate - self.scene.clone_environments(copy_from_source=False) + # build a homogeneous clone plan and replicate the env_0 layout to every env + src, dest = "/World/envs/env_0", "/World/envs/env_{}" + pos = cloner.grid_transforms(self.scene.num_envs, self.scene.cfg.env_spacing, device=self.device)[0] + plan = cloner.ClonePlan.from_env_0(src, dest, self.scene.num_envs, self.device, pos) + cloner.replicate(plan, stage=self.scene.stage) # we need to explicitly filter collisions for CPU simulation if self.device == "cpu": self.scene.filter_collisions(global_prim_paths=[]) From b441d4180762623297117e89aaa97a89d54e1c2d Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Mon, 8 Jun 2026 06:35:00 +0000 Subject: [PATCH 14/40] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 6.5.0 → 6.6.0 - isaaclab_contrib: 0.4.4 → 0.4.5 - isaaclab_newton: 0.15.2 → 0.15.3 - isaaclab_visualizers: 0.1.3 → 0.1.4 --- .../fix-mdl-texture-dependencies.rst | 4 -- .../replication-session-redesign.minor.rst | 49 --------------- .../yizew-support-multi-backends.rst | 14 ----- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 62 +++++++++++++++++++ source/isaaclab/pyproject.toml | 2 +- ...ix-newton-deformable-clone-replication.rst | 4 -- source/isaaclab_contrib/config/extension.toml | 2 +- source/isaaclab_contrib/docs/CHANGELOG.rst | 9 +++ source/isaaclab_contrib/pyproject.toml | 2 +- .../fix-newton-close-site-leak.rst | 4 -- .../replication-session-redesign.skip | 5 -- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 9 +++ source/isaaclab_newton/pyproject.toml | 2 +- .../replication-session-redesign.skip | 0 .../replication-session-redesign.skip | 5 -- .../replication-session-redesign.skip | 4 -- .../yizew-support-multi-backends.rst | 6 -- .../config/extension.toml | 2 +- .../isaaclab_visualizers/docs/CHANGELOG.rst | 11 ++++ source/isaaclab_visualizers/pyproject.toml | 2 +- 22 files changed, 99 insertions(+), 103 deletions(-) delete mode 100644 source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst delete mode 100644 source/isaaclab/changelog.d/replication-session-redesign.minor.rst delete mode 100644 source/isaaclab/changelog.d/yizew-support-multi-backends.rst delete mode 100644 source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst delete mode 100644 source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst delete mode 100644 source/isaaclab_newton/changelog.d/replication-session-redesign.skip delete mode 100644 source/isaaclab_ovphysx/changelog.d/replication-session-redesign.skip delete mode 100644 source/isaaclab_physx/changelog.d/replication-session-redesign.skip delete mode 100644 source/isaaclab_tasks/changelog.d/replication-session-redesign.skip delete mode 100644 source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst diff --git a/source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst b/source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst deleted file mode 100644 index e42b37ff69a6..000000000000 --- a/source/isaaclab/changelog.d/fix-mdl-texture-dependencies.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed remote asset mirroring to include textures referenced by downloaded MDL materials. diff --git a/source/isaaclab/changelog.d/replication-session-redesign.minor.rst b/source/isaaclab/changelog.d/replication-session-redesign.minor.rst deleted file mode 100644 index 598ceefabb2a..000000000000 --- a/source/isaaclab/changelog.d/replication-session-redesign.minor.rst +++ /dev/null @@ -1,49 +0,0 @@ -Added -^^^^^ - -* Added :data:`~isaaclab.cloner.REPLICATION_QUEUE` and the free function - :func:`~isaaclab.cloner.replicate`, the explicit registry-and-drain pair - that backends now hook into for replication. -* Added :meth:`~isaaclab.cloner.ClonePlan.from_env_0` for direct envs that - clone a single env-0 prototype across every env. -* Added :attr:`~isaaclab.cloner.CloneCfg.clone_regex` as the single source - of truth for the env-namespace convention (default ``"/World/envs/env_.*"``). - -Fixed -^^^^^ - -* Fixed :data:`~isaaclab.cloner.REPLICATION_QUEUE` leaking stale entries - when a backend or asset construction raised mid-session. - -Changed -^^^^^^^ - -* **Breaking:** Rewrote :class:`~isaaclab.cloner.ReplicateSession` as a thin - context manager around :func:`~isaaclab.cloner.make_clone_plan` and - :func:`~isaaclab.cloner.replicate`. The no-arg form and the cached - ``plan`` / ``cfg_rows`` / ``replicate_on_exit`` fields are gone. Direct - envs migrate to ``cloner.replicate(cloner.ClonePlan.from_env_0(...))``. -* **Breaking:** Changed :func:`~isaaclab.cloner.make_clone_plan` to take - ``cfgs`` and absorb the cfg-driven planning logic previously inside - :class:`~isaaclab.scene.InteractiveScene`, returning a self-contained - :class:`~isaaclab.cloner.ClonePlan`. -* **Breaking:** :func:`~isaaclab.cloner.replicate` and - :class:`~isaaclab.cloner.ReplicateSession` now require an explicit - ``stage=`` keyword; the :class:`~isaaclab.cloner.ClonePlan` is - stage-agnostic. -* Changed :attr:`~isaaclab.scene.InteractiveScene.env_origins` to read from - the published :class:`~isaaclab.cloner.ClonePlan`, making the plan the - single source of truth for env placement. - -Removed -^^^^^^^ - -* **Breaking:** Removed ``isaaclab.cloner.replicate_session_defaults`` and - ``isaaclab.cloner.replicate_session``. Use - :data:`~isaaclab.cloner.REPLICATION_QUEUE` and - :func:`~isaaclab.cloner.replicate` instead. -* **Breaking:** Removed :meth:`InteractiveScene.clone_environments`; direct - envs should use ``cloner.replicate(cloner.ClonePlan.from_env_0(...))``. -* **Breaking:** Removed :attr:`InteractiveScene.env_ns` and - :attr:`InteractiveScene.env_regex_ns`; read - :attr:`~isaaclab.cloner.CloneCfg.clone_regex` instead. diff --git a/source/isaaclab/changelog.d/yizew-support-multi-backends.rst b/source/isaaclab/changelog.d/yizew-support-multi-backends.rst deleted file mode 100644 index 3b07fde871f0..000000000000 --- a/source/isaaclab/changelog.d/yizew-support-multi-backends.rst +++ /dev/null @@ -1,14 +0,0 @@ -Added -^^^^^ - -* Added :attr:`~isaaclab.scene.InteractiveSceneCfg.class_type` so scene configs - can instantiate custom scene classes. -* Added :meth:`~isaaclab.sim.SimulationContext.is_headless_or_exist_active_visualizer` - to let kitless and external-visualizer demos share a visualizer-aware stepping - condition. - -Changed -^^^^^^^ - -* Updated demo scripts to support selectable PhysX or Newton MJWarp physics - backends and Kit or Newton visualizers. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index b360527edc03..adfe1a7e81f3 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "6.5.0" +version = "6.6.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index e2c217487ab2..2f4dcad4180d 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,68 @@ Changelog --------- +6.6.0 (2026-06-08) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :attr:`~isaaclab.scene.InteractiveSceneCfg.class_type` so scene configs + can instantiate custom scene classes. +* Added :meth:`~isaaclab.sim.SimulationContext.is_headless_or_exist_active_visualizer` + to let kitless and external-visualizer demos share a visualizer-aware stepping + condition. +* Added :data:`~isaaclab.cloner.REPLICATION_QUEUE` and the free function + :func:`~isaaclab.cloner.replicate`, the explicit registry-and-drain pair + that backends now hook into for replication. +* Added :meth:`~isaaclab.cloner.ClonePlan.from_env_0` for direct envs that + clone a single env-0 prototype across every env. +* Added :attr:`~isaaclab.cloner.CloneCfg.clone_regex` as the single source + of truth for the env-namespace convention (default ``"/World/envs/env_.*"``). + +Changed +^^^^^^^ + +* Updated demo scripts to support selectable PhysX or Newton MJWarp physics + backends and Kit or Newton visualizers. +* **Breaking:** Rewrote :class:`~isaaclab.cloner.ReplicateSession` as a thin + context manager around :func:`~isaaclab.cloner.make_clone_plan` and + :func:`~isaaclab.cloner.replicate`. The no-arg form and the cached + ``plan`` / ``cfg_rows`` / ``replicate_on_exit`` fields are gone. Direct + envs migrate to ``cloner.replicate(cloner.ClonePlan.from_env_0(...))``. +* **Breaking:** Changed :func:`~isaaclab.cloner.make_clone_plan` to take + ``cfgs`` and absorb the cfg-driven planning logic previously inside + :class:`~isaaclab.scene.InteractiveScene`, returning a self-contained + :class:`~isaaclab.cloner.ClonePlan`. +* **Breaking:** :func:`~isaaclab.cloner.replicate` and + :class:`~isaaclab.cloner.ReplicateSession` now require an explicit + ``stage=`` keyword; the :class:`~isaaclab.cloner.ClonePlan` is + stage-agnostic. +* Changed :attr:`~isaaclab.scene.InteractiveScene.env_origins` to read from + the published :class:`~isaaclab.cloner.ClonePlan`, making the plan the + single source of truth for env placement. + +Removed +^^^^^^^ + +* **Breaking:** Removed ``isaaclab.cloner.replicate_session_defaults`` and + ``isaaclab.cloner.replicate_session``. Use + :data:`~isaaclab.cloner.REPLICATION_QUEUE` and + :func:`~isaaclab.cloner.replicate` instead. +* **Breaking:** Removed :meth:`InteractiveScene.clone_environments`; direct + envs should use ``cloner.replicate(cloner.ClonePlan.from_env_0(...))``. +* **Breaking:** Removed :attr:`InteractiveScene.env_ns` and + :attr:`InteractiveScene.env_regex_ns`; read + :attr:`~isaaclab.cloner.CloneCfg.clone_regex` instead. + +Fixed +^^^^^ + +* Fixed remote asset mirroring to include textures referenced by downloaded MDL materials. +* Fixed :data:`~isaaclab.cloner.REPLICATION_QUEUE` leaking stale entries + when a backend or asset construction raised mid-session. + + 6.5.0 (2026-06-07) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/pyproject.toml b/source/isaaclab/pyproject.toml index 935d83f0f5b9..c9c7cbd4d64e 100644 --- a/source/isaaclab/pyproject.toml +++ b/source/isaaclab/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab" -version = "6.5.0" +version = "6.6.0" description = "Extension providing main framework interfaces and abstractions for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst b/source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst deleted file mode 100644 index a06cc9ca40af..000000000000 --- a/source/isaaclab_contrib/changelog.d/fix-newton-deformable-clone-replication.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed Newton deformable clone replication and Fabric particle sync setup. diff --git a/source/isaaclab_contrib/config/extension.toml b/source/isaaclab_contrib/config/extension.toml index 644f71728b00..63cf890ace87 100644 --- a/source/isaaclab_contrib/config/extension.toml +++ b/source/isaaclab_contrib/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.4.4" +version = "0.4.5" # Description title = "Isaac Lab External Contributions" diff --git a/source/isaaclab_contrib/docs/CHANGELOG.rst b/source/isaaclab_contrib/docs/CHANGELOG.rst index 9bb4124c7b3e..639fff17f6e3 100644 --- a/source/isaaclab_contrib/docs/CHANGELOG.rst +++ b/source/isaaclab_contrib/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +0.4.5 (2026-06-08) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed Newton deformable clone replication and Fabric particle sync setup. + + 0.4.4 (2026-06-06) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_contrib/pyproject.toml b/source/isaaclab_contrib/pyproject.toml index e8f06d9a9018..00dc87b8d4bd 100644 --- a/source/isaaclab_contrib/pyproject.toml +++ b/source/isaaclab_contrib/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_contrib" -version = "0.4.4" +version = "0.4.5" description = "An extension used to stage and integrate externally contributed features and implementations." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst b/source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst deleted file mode 100644 index 88b9a9d129ba..000000000000 --- a/source/isaaclab_newton/changelog.d/fix-newton-close-site-leak.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed stale Newton sensor site registrations leaking across simulation context teardown. diff --git a/source/isaaclab_newton/changelog.d/replication-session-redesign.skip b/source/isaaclab_newton/changelog.d/replication-session-redesign.skip deleted file mode 100644 index 4ff1bbe80281..000000000000 --- a/source/isaaclab_newton/changelog.d/replication-session-redesign.skip +++ /dev/null @@ -1,5 +0,0 @@ -Internal refactor: ``queue_newton_physics_replication`` now appends ``(cfg, -NewtonReplicateContext)`` to :data:`isaaclab.cloner.REPLICATION_QUEUE` instead of -reaching into the now-removed module-level replication session. No user-visible -behavior change — :func:`~isaaclab.cloner.replicate` still drives Newton replication -via :class:`NewtonReplicateContext` exactly as before. diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index a0dccd8b9942..fefc0e5ce3f1 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.15.2" +version = "0.15.3" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index a1f4c0d6b4c5..3f87dce484e1 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +0.15.3 (2026-06-08) +~~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed stale Newton sensor site registrations leaking across simulation context teardown. + + 0.15.2 (2026-06-06) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/pyproject.toml b/source/isaaclab_newton/pyproject.toml index 3a2c575f91cd..300ae1baecef 100644 --- a/source/isaaclab_newton/pyproject.toml +++ b/source/isaaclab_newton/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_newton" -version = "0.15.2" +version = "0.15.3" description = "Extension providing IsaacLab with Newton specific abstractions." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_ovphysx/changelog.d/replication-session-redesign.skip b/source/isaaclab_ovphysx/changelog.d/replication-session-redesign.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_physx/changelog.d/replication-session-redesign.skip b/source/isaaclab_physx/changelog.d/replication-session-redesign.skip deleted file mode 100644 index 8b9f8ee958aa..000000000000 --- a/source/isaaclab_physx/changelog.d/replication-session-redesign.skip +++ /dev/null @@ -1,5 +0,0 @@ -Internal refactor: ``queue_physx_replication`` now appends ``(cfg, -PhysxReplicateContext)`` to :data:`isaaclab.cloner.REPLICATION_QUEUE` instead of -reaching into the now-removed module-level replication session. No user-visible -behavior change — :func:`~isaaclab.cloner.replicate` still drives PhysX replication -via :class:`PhysxReplicateContext` exactly as before. diff --git a/source/isaaclab_tasks/changelog.d/replication-session-redesign.skip b/source/isaaclab_tasks/changelog.d/replication-session-redesign.skip deleted file mode 100644 index c34b8831ae8d..000000000000 --- a/source/isaaclab_tasks/changelog.d/replication-session-redesign.skip +++ /dev/null @@ -1,4 +0,0 @@ -Internal refactor: every direct env's ``_setup_scene`` now calls -``cloner.replicate(cloner.ClonePlan.from_env_0(...))`` after asset -construction in place of the prior ``with cloner.ReplicateSession():`` wrapper. -No user-visible behavior change. diff --git a/source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst b/source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst deleted file mode 100644 index 7a1cd353d7ec..000000000000 --- a/source/isaaclab_visualizers/changelog.d/yizew-support-multi-backends.rst +++ /dev/null @@ -1,6 +0,0 @@ -Added -^^^^^ - -* Added :meth:`~isaaclab_visualizers.newton.NewtonVisualizer.set_camera_view` so - the Newton visualizer follows :meth:`~isaaclab.sim.SimulationContext.set_camera_view` - camera updates. diff --git a/source/isaaclab_visualizers/config/extension.toml b/source/isaaclab_visualizers/config/extension.toml index daa19cd5ef58..a3d33879c36b 100644 --- a/source/isaaclab_visualizers/config/extension.toml +++ b/source/isaaclab_visualizers/config/extension.toml @@ -1,7 +1,7 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.1.3" +version = "0.1.4" # Description category = "isaaclab" diff --git a/source/isaaclab_visualizers/docs/CHANGELOG.rst b/source/isaaclab_visualizers/docs/CHANGELOG.rst index 346f8941b3bd..10c9f91b491f 100644 --- a/source/isaaclab_visualizers/docs/CHANGELOG.rst +++ b/source/isaaclab_visualizers/docs/CHANGELOG.rst @@ -1,6 +1,17 @@ Changelog --------- +0.1.4 (2026-06-08) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :meth:`~isaaclab_visualizers.newton.NewtonVisualizer.set_camera_view` so + the Newton visualizer follows :meth:`~isaaclab.sim.SimulationContext.set_camera_view` + camera updates. + + 0.1.3 (2026-06-06) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_visualizers/pyproject.toml b/source/isaaclab_visualizers/pyproject.toml index 317e26d29810..fc86bbaa57d9 100644 --- a/source/isaaclab_visualizers/pyproject.toml +++ b/source/isaaclab_visualizers/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab-visualizers" -version = "0.1.3" +version = "0.1.4" description = "Visualizer backends for Isaac Lab (Kit, Newton, Rerun, Viser)." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] From 1e05161589a06cbca8181ba944959ba0d561cc25 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Mon, 8 Jun 2026 07:44:28 +0100 Subject: [PATCH 15/40] Fix OvPhysX missing runtime error (#5995) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Adds an OvPhysX runtime import helper so missing optional `ovphysx` wheel failures report the supported install command instead of a raw `No module named ovphysx` error. This routes `isaaclab_ovphysx.tensor_types` and `OvPhysxManager` bootstrap imports through the helper, preserves nested missing-dependency errors, updates the OvPhysX backend docs, and adds a focused regression test. Related to #5991. Fixes: N/A ## Type of change - Bug fix (non-breaking change which fixes an issue) - Documentation update ## Screenshots N/A ## Validation - `./isaaclab.sh -p -m pytest source/isaaclab_ovphysx/test/test_runtime_imports.py` -> 2 passed - `SKIP=check-git-lfs-pointers ./isaaclab.sh -f` -> passed - `./isaaclab.sh -f` was attempted before commit and before push; it fails only at `check-git-lfs-pointers` because `git-lfs` is not installed in this local environment. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../physical-backends/ovphysx/index.rst | 3 +- .../antoiner-ovphysx-runtime-guard.rst | 5 +++ .../isaaclab_ovphysx/_runtime.py | 38 +++++++++++++++++ .../physics/ovphysx_manager.py | 7 ++-- .../isaaclab_ovphysx/tensor_types.py | 4 +- .../test/test_runtime_imports.py | 42 +++++++++++++++++++ 6 files changed, 94 insertions(+), 5 deletions(-) create mode 100644 source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst create mode 100644 source/isaaclab_ovphysx/isaaclab_ovphysx/_runtime.py create mode 100644 source/isaaclab_ovphysx/test/test_runtime_imports.py diff --git a/docs/source/overview/core-concepts/physical-backends/ovphysx/index.rst b/docs/source/overview/core-concepts/physical-backends/ovphysx/index.rst index fe11901be1cd..a6395655dd72 100644 --- a/docs/source/overview/core-concepts/physical-backends/ovphysx/index.rst +++ b/docs/source/overview/core-concepts/physical-backends/ovphysx/index.rst @@ -87,7 +87,8 @@ You can also install all OV runtime wheels with: The ``ov[ovphysx]`` selector installs ``source/isaaclab_ovphysx`` with its ``[ovphysx]`` extra. If the wheel is missing, OvPhysX-specific tests skip with -``ovphysx wheel not installed`` and user code fails at import time. +``ovphysx wheel not installed`` and user code raises an install hint when it +first imports the runtime-backed modules. Testing the Installation ------------------------ diff --git a/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst b/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst new file mode 100644 index 000000000000..ed997b81bb0d --- /dev/null +++ b/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Added an actionable install error when the optional ``ovphysx`` runtime wheel + is missing from the :mod:`isaaclab_ovphysx` backend. diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/_runtime.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/_runtime.py new file mode 100644 index 000000000000..fc7322fa32c1 --- /dev/null +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/_runtime.py @@ -0,0 +1,38 @@ +# 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 + +"""Helpers for loading optional OvPhysX runtime modules.""" + +from __future__ import annotations + +import importlib +from types import ModuleType + +_OVPHYSX_INSTALL_MESSAGE = ( + "The OvPhysX backend requires the optional 'ovphysx' runtime wheel, which is not installed. " + "Install it with: ./isaaclab.sh -i 'ov[ovphysx]' " + "(or, manually: pip install --extra-index-url https://pypi.nvidia.com " + "-e 'source/isaaclab_ovphysx[ovphysx]')." +) + + +def import_ovphysx(module_name: str = "ovphysx") -> ModuleType: + """Import an optional ``ovphysx`` runtime module with an actionable install error. + + Args: + module_name: Name of the ``ovphysx`` module to import. + + Returns: + The imported runtime module. + + Raises: + ModuleNotFoundError: If the optional ``ovphysx`` runtime wheel is not installed. + """ + try: + return importlib.import_module(module_name) + except ModuleNotFoundError as exc: + if exc.name != "ovphysx": + raise + raise ModuleNotFoundError(_OVPHYSX_INSTALL_MESSAGE, name="ovphysx") from exc diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py index 8fc63190a795..160f6a12abc8 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/physics/ovphysx_manager.py @@ -27,6 +27,8 @@ from isaaclab.physics import PhysicsEvent, PhysicsManager from isaaclab.scene_data import SceneDataBackend, SceneDataFormat +from isaaclab_ovphysx._runtime import import_ovphysx + if TYPE_CHECKING: from isaaclab.sim.simulation_context import SimulationContext @@ -626,13 +628,12 @@ def _construct_physx(cls, ovphysx_device: str, gpu_index: int) -> None: _hidden_pxr = {k: _sys.modules.pop(k) for k in list(_sys.modules) if k == "pxr" or k.startswith("pxr.")} try: - import ovphysx as _ovphysx_bootstrap - + _ovphysx_bootstrap = import_ovphysx() _ovphysx_bootstrap.bootstrap() finally: _sys.modules.update(_hidden_pxr) - import ovphysx + ovphysx = import_ovphysx() physx_kwargs = {"device": ovphysx_device} physx_signature = inspect.signature(ovphysx.PhysX) diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/tensor_types.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/tensor_types.py index 9e7df44aef9a..a208af36ae62 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/tensor_types.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/tensor_types.py @@ -16,7 +16,9 @@ always safe to import regardless of USD state or native library loading. """ -from ovphysx.types import TensorType # noqa: F401 — re-exported for new code +from isaaclab_ovphysx._runtime import import_ovphysx + +TensorType = import_ovphysx("ovphysx.types").TensorType _TT = TensorType # shorter reference for alias block diff --git a/source/isaaclab_ovphysx/test/test_runtime_imports.py b/source/isaaclab_ovphysx/test/test_runtime_imports.py new file mode 100644 index 000000000000..54bfdc5efa5e --- /dev/null +++ b/source/isaaclab_ovphysx/test/test_runtime_imports.py @@ -0,0 +1,42 @@ +# 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 + +"""Tests for optional OvPhysX runtime imports.""" + +import importlib + +import pytest +from isaaclab_ovphysx._runtime import _OVPHYSX_INSTALL_MESSAGE, import_ovphysx + + +def test_import_ovphysx_reports_install_command_when_runtime_missing(monkeypatch): + """Missing root ``ovphysx`` imports raise the Isaac Lab install hint.""" + + def import_module_raises_missing_ovphysx(module_name: str): + raise ModuleNotFoundError("No module named 'ovphysx'", name="ovphysx") + + monkeypatch.setattr(importlib, "import_module", import_module_raises_missing_ovphysx) + + with pytest.raises(ModuleNotFoundError) as exc_info: + import_ovphysx("ovphysx.types") + + assert str(exc_info.value) == _OVPHYSX_INSTALL_MESSAGE + assert exc_info.value.name == "ovphysx" + assert exc_info.value.__cause__.name == "ovphysx" + + +def test_import_ovphysx_preserves_nested_missing_dependency(monkeypatch): + """Missing dependencies inside ``ovphysx`` are not rewritten as install hints.""" + + def import_module_raises_missing_dependency(module_name: str): + raise ModuleNotFoundError("No module named 'carb'", name="carb") + + monkeypatch.setattr(importlib, "import_module", import_module_raises_missing_dependency) + + with pytest.raises(ModuleNotFoundError) as exc_info: + import_ovphysx() + + assert exc_info.value.name == "carb" + assert "carb" in str(exc_info.value) From 88bd0ec7203d67f59a8a5ff3daab4b779a77c5c9 Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Mon, 8 Jun 2026 18:39:54 +0800 Subject: [PATCH 16/40] Makes documentation commands more platform agnostic (#6023) # Description Updates applicable commands in documentation to use python instead of platform specific isaaclab.sh/.bat scripts. Include windows commands where needed. ## Type of change - Documentation update ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Signed-off-by: Kelly Guo Co-authored-by: greptile-apps[bot] <165735046+greptile-apps[bot]@users.noreply.github.com> --- docs/source/how-to/add_own_library.rst | 24 +-- docs/source/how-to/configure_rendering.rst | 2 +- docs/source/how-to/draw_markers.rst | 2 +- .../estimate_how_many_cameras_can_run.rst | 20 +-- docs/source/how-to/haply_teleoperation.rst | 27 +--- docs/source/how-to/import_new_asset.rst | 142 +++++++++--------- docs/source/how-to/multi_asset_spawning.rst | 2 +- docs/source/how-to/profile_with_nsys.rst | 6 +- docs/source/how-to/record_animation.rst | 26 +++- docs/source/how-to/save_camera_output.rst | 4 +- .../source/how-to/visualizer_tiled_camera.rst | 11 +- .../include/src_python_virtual_env.rst | 5 +- docs/source/setup/quickstart.rst | 4 +- docs/source/tutorials/00_sim/create_empty.rst | 4 +- .../03_envs/create_manager_rl_env.rst | 2 +- 15 files changed, 129 insertions(+), 152 deletions(-) diff --git a/docs/source/how-to/add_own_library.rst b/docs/source/how-to/add_own_library.rst index d5aa8aa05158..c454bc16b7bd 100644 --- a/docs/source/how-to/add_own_library.rst +++ b/docs/source/how-to/add_own_library.rst @@ -33,7 +33,7 @@ For instance, if you want to use your own modified version of the `rsl-rl`_ libr cd IsaacLab # Note: If you are using a virtual environment, make sure to activate it before running the following command - ./isaaclab.sh -p -m pip install -e /path/to/rsl_rl + python -m pip install -e /path/to/rsl_rl In this case, the ``rsl-rl`` library will be installed in the Python environment used by Isaac Lab. You can now use the ``rsl-rl`` library in your experiments. To check the library version and other details, you can use the following @@ -41,23 +41,23 @@ command: .. code-block:: bash - ./isaaclab.sh -p -m pip show rsl-rl-lib + python -m pip show rsl-rl-lib This should now show the location of the ``rsl-rl`` library as the directory where you cloned the library. For instance, if you cloned the library to ``/home/user/git/rsl_rl``, the output of the above command should be: .. code-block:: bash - Name: rsl_rl - Version: 3.0.1 - Summary: Fast and simple RL algorithms implemented in pytorch - Home-page: https://github.com/leggedrobotics/rsl_rl - Author: ETH Zurich, NVIDIA CORPORATION - Author-email: - License: BSD-3 - Location: /home/user/git/rsl_rl - Requires: torch, torchvision, numpy, GitPython, onnx - Required-by: + Name: rsl_rl + Version: 3.0.1 + Summary: Fast and simple RL algorithms implemented in pytorch + Home-page: https://github.com/leggedrobotics/rsl_rl + Author: ETH Zurich, NVIDIA CORPORATION + Author-email: + License: BSD-3 + Location: /home/user/git/rsl_rl + Requires: torch, torchvision, numpy, GitPython, onnx + Required-by: Integrating a new library diff --git a/docs/source/how-to/configure_rendering.rst b/docs/source/how-to/configure_rendering.rst index ee2510fdc44c..78b8cdea9dac 100644 --- a/docs/source/how-to/configure_rendering.rst +++ b/docs/source/how-to/configure_rendering.rst @@ -31,7 +31,7 @@ Rendering modes can be selected in 2 ways. .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/00_sim/set_rendering_mode.py --rendering_mode {performance/balanced/quality} + python scripts/tutorials/00_sim/set_rendering_mode.py --rendering_mode {performance/balanced/quality} Note, the ``rendering_mode`` defaults to ``balanced``. diff --git a/docs/source/how-to/draw_markers.rst b/docs/source/how-to/draw_markers.rst index 58b1e0ed3790..d2d4cf45593b 100644 --- a/docs/source/how-to/draw_markers.rst +++ b/docs/source/how-to/draw_markers.rst @@ -66,7 +66,7 @@ To run the accompanying script, execute the following command: .. code-block:: bash - ./isaaclab.sh -p scripts/demos/markers.py + python scripts/demos/markers.py The simulation should start, and you can observe the different types of markers arranged in a grid pattern. The markers will rotating around their respective axes. Additionally every few rotations, they will diff --git a/docs/source/how-to/estimate_how_many_cameras_can_run.rst b/docs/source/how-to/estimate_how_many_cameras_can_run.rst index 080ed96b78c5..58558c2eb56f 100644 --- a/docs/source/how-to/estimate_how_many_cameras_can_run.rst +++ b/docs/source/how-to/estimate_how_many_cameras_can_run.rst @@ -41,7 +41,7 @@ First, run .. code-block:: bash - ./isaaclab.sh -p scripts/benchmarks/benchmark_cameras.py -h + python scripts/benchmarks/benchmark_cameras.py -h to see all possible parameters you can vary with this utility. @@ -61,12 +61,9 @@ only in RGB mode, run .. code-block:: bash - ./isaaclab.sh -p scripts/benchmarks/benchmark_cameras.py \ - --task Isaac-Cartpole --num_tiled_cameras 100 \ - --task_num_cameras_per_env 2 \ - --tiled_camera_data_types rgb + python scripts/benchmarks/benchmark_cameras.py --task Isaac-Cartpole --num_tiled_cameras 100 --task_num_cameras_per_env 2 --tiled_camera_data_types rgb -If you have pynvml installed, (``./isaaclab.sh -p -m pip install pynvml``), you can also +If you have pynvml installed, (``python -m pip install pynvml``), you can also find the maximum number of cameras that you could run in the specified environment up to a certain performance threshold (specified by max CPU utilization percent, max RAM utilization percent, max GPU compute percent, and max GPU memory percent). For example, to find the maximum number of cameras @@ -74,11 +71,7 @@ you can run with cartpole, you could run: .. code-block:: bash - ./isaaclab.sh -p scripts/benchmarks/benchmark_cameras.py \ - --task Isaac-Cartpole --num_tiled_cameras 100 \ - --task_num_cameras_per_env 2 \ - --tiled_camera_data_types rgb --autotune \ - --autotune_max_percentage_util 100 80 50 50 + python scripts/benchmarks/benchmark_cameras.py --task Isaac-Cartpole --num_tiled_cameras 100 --task_num_cameras_per_env 2 --tiled_camera_data_types rgb --autotune --autotune_max_percentage_util 100 80 50 50 Autotune may lead to the program crashing, which means that it tried to run too many cameras at once. However, the max percentage utilization parameter is meant to prevent this from happening. @@ -97,10 +90,7 @@ For example, to view 100 random objects with 2 standard cameras, one could run .. code-block:: bash - ./isaaclab.sh -p scripts/benchmarks/benchmark_cameras.py \ - --height 100 --width 100 --num_standard_cameras 2 \ - --standard_camera_data_types instance_segmentation_fast normals --num_objects 100 \ - --experiment_length 100 + python scripts/benchmarks/benchmark_cameras.py --height 100 --width 100 --num_standard_cameras 2 --standard_camera_data_types instance_segmentation_fast normals --num_objects 100 --experiment_length 100 If your system cannot handle this due to performance reasons, then the process will be killed. It's recommended to monitor CPU/RAM utilization and GPU utilization while running this script, to get diff --git a/docs/source/how-to/haply_teleoperation.rst b/docs/source/how-to/haply_teleoperation.rst index 46651077e338..d4df3b5edab3 100644 --- a/docs/source/how-to/haply_teleoperation.rst +++ b/docs/source/how-to/haply_teleoperation.rst @@ -156,24 +156,10 @@ a Franka Panda arm. Basic Usage ~~~~~~~~~~~ -.. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: bash - - # Ensure Haply SDK is running - ./isaaclab.sh -p scripts/demos/haply_teleoperation.py --websocket_uri ws://localhost:10001 --pos_sensitivity 1.65 - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: batch +.. code:: bash - REM Ensure Haply SDK is running - isaaclab.bat -p scripts\demos\haply_teleoperation.py --websocket_uri ws://localhost:10001 --pos_sensitivity 1.65 + # Ensure Haply SDK is running + python scripts/demos/haply_teleoperation.py --websocket_uri ws://localhost:10001 --pos_sensitivity 1.65 The demo will: @@ -198,13 +184,10 @@ Customize the demo with command-line arguments: .. code:: bash # Use custom WebSocket URI - ./isaaclab.sh -p scripts/demos/haply_teleoperation.py \ - --websocket_uri ws://192.168.1.100:10001 + python scripts/demos/haply_teleoperation.py --websocket_uri ws://192.168.1.100:10001 # Adjust position sensitivity (default: 1.0) - ./isaaclab.sh -p scripts/demos/haply_teleoperation.py \ - --websocket_uri ws://localhost:10001 \ - --pos_sensitivity 2.0 + python scripts/demos/haply_teleoperation.py --websocket_uri ws://localhost:10001 --pos_sensitivity 2.0 Demo Features ~~~~~~~~~~~~~ diff --git a/docs/source/how-to/import_new_asset.rst b/docs/source/how-to/import_new_asset.rst index 4ed6c4241c30..92a28e4c1b54 100644 --- a/docs/source/how-to/import_new_asset.rst +++ b/docs/source/how-to/import_new_asset.rst @@ -144,40 +144,40 @@ The following shows the steps to clone the repository and run the converter: .. code-block:: bash - # clone a repository with URDF files - git clone git@github.com:isaac-orbit/anymal_d_simple_description.git - - # go to top of the Isaac Lab repository - cd IsaacLab - # run the converter - ./isaaclab.sh -p scripts/tools/convert_urdf.py \ - ../anymal_d_simple_description/urdf/anymal.urdf \ - source/isaaclab_assets/data/Robots/ANYbotics/ \ - --merge-joints \ - --joint-stiffness 0.0 \ - --joint-damping 0.0 \ - --joint-target-type none \ - --viz kit + # clone a repository with URDF files + git clone git@github.com:isaac-orbit/anymal_d_simple_description.git + + # go to top of the Isaac Lab repository + cd IsaacLab + # run the converter + python scripts/tools/convert_urdf.py \ + ../anymal_d_simple_description/urdf/anymal.urdf \ + source/isaaclab_assets/data/Robots/ANYbotics/ \ + --merge-joints \ + --joint-stiffness 0.0 \ + --joint-damping 0.0 \ + --joint-target-type none \ + --viz kit .. tab-item:: :icon:`fa-brands fa-windows` Windows :sync: windows .. code-block:: batch - :: clone a repository with URDF files - git clone git@github.com:isaac-orbit/anymal_d_simple_description.git - - :: go to top of the Isaac Lab repository - cd IsaacLab - :: run the converter - isaaclab.bat -p scripts\tools\convert_urdf.py ^ - ..\anymal_d_simple_description\urdf\anymal.urdf ^ - source\isaaclab_assets\data\Robots\ANYbotics\ ^ - --merge-joints ^ - --joint-stiffness 0.0 ^ - --joint-damping 0.0 ^ - --joint-target-type none ^ - --viz kit + :: clone a repository with URDF files + git clone git@github.com:isaac-orbit/anymal_d_simple_description.git + + :: go to top of the Isaac Lab repository + cd IsaacLab + :: run the converter + python scripts\tools\convert_urdf.py ^ + ..\anymal_d_simple_description\urdf\anymal.urdf ^ + source\isaaclab_assets\data\Robots\ANYbotics\ ^ + --merge-joints ^ + --joint-stiffness 0.0 ^ + --joint-damping 0.0 ^ + --joint-target-type none ^ + --viz kit Executing the above script will create a USD file inside the ``source/isaaclab_assets/data/Robots/ANYbotics/anymal/`` directory (the subdirectory name @@ -298,34 +298,34 @@ The following shows the steps to clone the repository and run the converter: .. code-block:: bash - # clone a repository with MJCF files - git clone git@github.com:google-deepmind/mujoco_menagerie.git + # clone a repository with MJCF files + git clone git@github.com:google-deepmind/mujoco_menagerie.git - # go to top of the Isaac Lab repository - cd IsaacLab - # run the converter - ./isaaclab.sh -p scripts/tools/convert_mjcf.py \ - ../mujoco_menagerie/unitree_h1/h1.xml \ - source/isaaclab_assets/data/Robots/Unitree/h1.usd \ - --merge-mesh \ - --viz kit + # go to top of the Isaac Lab repository + cd IsaacLab + # run the converter + python scripts/tools/convert_mjcf.py \ + ../mujoco_menagerie/unitree_h1/h1.xml \ + source/isaaclab_assets/data/Robots/Unitree/h1.usd \ + --merge-mesh \ + --viz kit .. tab-item:: :icon:`fa-brands fa-windows` Windows :sync: windows .. code-block:: batch - :: clone a repository with MJCF files - git clone git@github.com:google-deepmind/mujoco_menagerie.git + :: clone a repository with MJCF files + git clone git@github.com:google-deepmind/mujoco_menagerie.git - :: go to top of the Isaac Lab repository - cd IsaacLab - :: run the converter - isaaclab.bat -p scripts\tools\convert_mjcf.py ^ - ..\mujoco_menagerie\unitree_h1\h1.xml ^ - source\isaaclab_assets\data\Robots\Unitree\h1.usd ^ - --merge-mesh ^ - --viz kit + :: go to top of the Isaac Lab repository + cd IsaacLab + :: run the converter + python scripts\tools\convert_mjcf.py ^ + ..\mujoco_menagerie\unitree_h1\h1.xml ^ + source\isaaclab_assets\data\Robots\Unitree\h1.usd ^ + --merge-mesh ^ + --viz kit Executing the above script will create the USD file inside the ``source/isaaclab_assets/data/Robots/Unitree/`` directory: @@ -434,36 +434,36 @@ the steps to clone the repository and run the converter: .. code-block:: bash - # clone a repository with URDF files - git clone git@github.com:NVIDIA-Omniverse/IsaacGymEnvs.git + # clone a repository with mesh files + git clone git@github.com:NVIDIA-Omniverse/IsaacGymEnvs.git - # go to top of the Isaac Lab repository - cd IsaacLab - # run the converter - ./isaaclab.sh -p scripts/tools/convert_mesh.py \ - ../IsaacGymEnvs/assets/trifinger/objects/meshes/cube_multicolor.obj \ - source/isaaclab_assets/data/Props/CubeMultiColor/cube_multicolor.usd \ - --make-instanceable \ - --collision-approximation convexDecomposition \ - --mass 1.0 + # go to top of the Isaac Lab repository + cd IsaacLab + # run the converter + python scripts/tools/convert_mesh.py \ + ../IsaacGymEnvs/assets/trifinger/objects/meshes/cube_multicolor.obj \ + source/isaaclab_assets/data/Props/CubeMultiColor/cube_multicolor.usd \ + --make-instanceable \ + --collision-approximation convexDecomposition \ + --mass 1.0 .. tab-item:: :icon:`fa-brands fa-windows` Windows :sync: windows .. code-block:: batch - :: clone a repository with URDF files - git clone git@github.com:NVIDIA-Omniverse/IsaacGymEnvs.git - - :: go to top of the Isaac Lab repository - cd IsaacLab - :: run the converter - isaaclab.bat -p scripts\tools\convert_mesh.py ^ - ..\IsaacGymEnvs\assets\trifinger\objects\meshes\cube_multicolor.obj ^ - source\isaaclab_assets\data\Props\CubeMultiColor\cube_multicolor.usd ^ - --make-instanceable ^ - --collision-approximation convexDecomposition ^ - --mass 1.0 + :: clone a repository with mesh files + git clone git@github.com:NVIDIA-Omniverse/IsaacGymEnvs.git + + :: go to top of the Isaac Lab repository + cd IsaacLab + :: run the converter + python scripts\tools\convert_mesh.py ^ + ..\IsaacGymEnvs\assets\trifinger\objects\meshes\cube_multicolor.obj ^ + source\isaaclab_assets\data\Props\CubeMultiColor\cube_multicolor.usd ^ + --make-instanceable ^ + --collision-approximation convexDecomposition ^ + --mass 1.0 You may need to press 'F' to zoom in on the asset after import. diff --git a/docs/source/how-to/multi_asset_spawning.rst b/docs/source/how-to/multi_asset_spawning.rst index 650b641bd684..a93fd5a3274b 100644 --- a/docs/source/how-to/multi_asset_spawning.rst +++ b/docs/source/how-to/multi_asset_spawning.rst @@ -125,7 +125,7 @@ To execute the script with multiple environments and randomized assets, use the .. code-block:: bash - ./isaaclab.sh -p scripts/demos/multi_asset.py --num_envs 2048 + python scripts/demos/multi_asset.py --num_envs 2048 This command runs the simulation with 2048 environments, each with randomly selected assets. To stop the simulation, you can close the window, or press ``Ctrl+C`` in the terminal. diff --git a/docs/source/how-to/profile_with_nsys.rst b/docs/source/how-to/profile_with_nsys.rst index bc2e843c516f..57f79bb32c6a 100644 --- a/docs/source/how-to/profile_with_nsys.rst +++ b/docs/source/how-to/profile_with_nsys.rst @@ -28,7 +28,7 @@ Prerequisites .. code-block:: bash - ./isaaclab.sh -p -m pip install nvtx + python -m pip install nvtx Running a Profile @@ -88,7 +88,7 @@ After editing the JSON, run the sync test to confirm every entry resolves: .. code-block:: bash - ./isaaclab.sh -p -m pytest scripts/benchmarks/test/test_nsys_trace.py + python -m pytest scripts/benchmarks/test/test_nsys_trace.py Troubleshooting @@ -96,7 +96,7 @@ Troubleshooting - **An expected domain doesn't appear in the timeline:** - - Confirm ``nvtx`` is installed in your Isaac Lab environment (``./isaaclab.sh -p -m pip show nvtx``). + - Confirm ``nvtx`` is installed in your Isaac Lab environment (``python -m pip show nvtx``). - Make sure the function is actually called during the profiled run. - Verify the JSON entry by running the sync test (above). diff --git a/docs/source/how-to/record_animation.rst b/docs/source/how-to/record_animation.rst index 590594034e44..008415614ce3 100644 --- a/docs/source/how-to/record_animation.rst +++ b/docs/source/how-to/record_animation.rst @@ -54,7 +54,7 @@ In standalone Isaac Lab environments, pass the ``--disable_fabric`` flag: .. code-block:: bash - ./isaaclab.sh -p scripts/environments/state_machine/lift_cube_sm.py --num_envs 8 --device cpu --disable_fabric --viz kit + python scripts/environments/state_machine/lift_cube_sm.py --num_envs 8 --device cpu --disable_fabric --viz kit After launching, the Isaac Lab UI window will display a "Record Animation" button. Click to begin recording. Click again to stop. @@ -64,11 +64,24 @@ The following files are saved to the ``recordings/`` folder: - ``Stage.usd`` — the original stage with physics disabled - ``TimeSample_tk001.usd`` — the animation (time-sampled) layer -To play back: +To play back, open Isaac Sim: -.. code-block:: bash +.. tab-set:: + :sync-group: os + + .. tab-item:: :icon:`fa-brands fa-linux` Linux + :sync: linux + + .. code-block:: bash + + ./isaaclab.sh -s + + .. tab-item:: :icon:`fa-brands fa-windows` Windows + :sync: windows + + .. code-block:: batch - ./isaaclab.sh -s # Opens Isaac Sim + isaaclab.bat -s Inside the Layers panel, insert both ``Stage.usd`` and ``TimeSample_tk001.usd`` as sublayers. The animation will now play back when you hit the play button. @@ -101,10 +114,7 @@ To record an animation: .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/03_envs/run_cartpole_rl_env.py \ - --anim_recording_enabled \ - --anim_recording_start_time 1 \ - --anim_recording_stop_time 3 + python scripts/tutorials/03_envs/run_cartpole_rl_env.py --anim_recording_enabled --anim_recording_start_time 1 --anim_recording_stop_time 3 .. note:: diff --git a/docs/source/how-to/save_camera_output.rst b/docs/source/how-to/save_camera_output.rst index 01b404efc0d8..acd1fea917f2 100644 --- a/docs/source/how-to/save_camera_output.rst +++ b/docs/source/how-to/save_camera_output.rst @@ -92,10 +92,10 @@ To run the accompanying script, execute the following command: .. code-block:: bash # Usage with saving and drawing - ./isaaclab.sh -p scripts/tutorials/04_sensors/run_usd_camera.py --save --draw --enable_cameras + python scripts/tutorials/04_sensors/run_usd_camera.py --save --draw --enable_cameras # Usage with saving only in headless mode - ./isaaclab.sh -p scripts/tutorials/04_sensors/run_usd_camera.py --save --headless --enable_cameras + python scripts/tutorials/04_sensors/run_usd_camera.py --save --headless --enable_cameras The simulation should start, and you can observe different objects falling down. An output folder will be created diff --git a/docs/source/how-to/visualizer_tiled_camera.rst b/docs/source/how-to/visualizer_tiled_camera.rst index d2193bf33d89..0bf2e0993e04 100644 --- a/docs/source/how-to/visualizer_tiled_camera.rst +++ b/docs/source/how-to/visualizer_tiled_camera.rst @@ -59,11 +59,7 @@ To run the tutorial with the args for this example, use: .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py \ - --enable_cameras \ - --task Isaac-Velocity-Rough-Anymal-D-v0 \ - --num_envs 256 \ - --viz kit + python scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py --enable_cameras --task Isaac-Velocity-Rough-Anymal-D-v0 --num_envs 256 --viz kit Within the script, you’ll find the ``KitVisualizerCfg`` configuration used to generate this example. You can use this config as a template for your own use @@ -110,10 +106,7 @@ To launch this example, run: .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py \ - --task Isaac-Stack-Cube-Galbot-Left-Arm-Gripper-Visuomotor-v0 \ - --num_envs 25 \ - --viz newton + python scripts/tutorials/07_visualizers/run_tiled_camera_visualizer.py --task Isaac-Stack-Cube-Galbot-Left-Arm-Gripper-Visuomotor-v0 --num_envs 25 --viz newton Within the script, the ``NewtonVisualizerCfg`` is configured to stream images from the existing camera sensor located at diff --git a/docs/source/setup/installation/include/src_python_virtual_env.rst b/docs/source/setup/installation/include/src_python_virtual_env.rst index 5ec5543b898f..6826397f6223 100644 --- a/docs/source/setup/installation/include/src_python_virtual_env.rst +++ b/docs/source/setup/installation/include/src_python_virtual_env.rst @@ -131,5 +131,6 @@ instead of *./isaaclab.sh -p* or *isaaclab.bat -p*. Once you are in the virtual environment, you do not need to use ``./isaaclab.sh -p`` or ``isaaclab.bat -p`` to run python scripts. You can use the default python executable in your -environment by running ``python`` or ``python3``. However, for the rest of the documentation, -we will assume that you are using ``./isaaclab.sh -p`` or ``isaaclab.bat -p`` to run python scripts. +environment by running ``python`` or ``python3``. Updated how-to guides use ``python`` directly; +older pages may still show ``./isaaclab.sh -p`` or ``isaaclab.bat -p``, which are equivalent when +your virtual environment is active. diff --git a/docs/source/setup/quickstart.rst b/docs/source/setup/quickstart.rst index 1a1676b5ee89..b1d98453fbb0 100644 --- a/docs/source/setup/quickstart.rst +++ b/docs/source/setup/quickstart.rst @@ -130,8 +130,8 @@ Add ``--headless`` to disable the GUI. Use ``--help`` on any script to see task- Next Steps ---------- -- List registered environments: ``./isaaclab.sh -p scripts/environments/list_envs.py`` -- Scaffold a new project: ``./isaaclab.sh --new`` +- List registered environments: ``python scripts/environments/list_envs.py`` +- Scaffold a new project: ``./isaaclab.sh --new`` (Linux) or ``isaaclab.bat --new`` (Windows) - Walk through tutorials: :doc:`/source/tutorials/index` - Browse all environments: :doc:`/source/overview/environments` diff --git a/docs/source/tutorials/00_sim/create_empty.rst b/docs/source/tutorials/00_sim/create_empty.rst index e65876a0f997..e2b9788d7f86 100644 --- a/docs/source/tutorials/00_sim/create_empty.rst +++ b/docs/source/tutorials/00_sim/create_empty.rst @@ -139,7 +139,7 @@ Now that we have gone through the code, let's run the script and see the result: .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/00_sim/create_empty.py --viz kit + python scripts/tutorials/00_sim/create_empty.py --viz kit The simulation should be playing, and the stage should be rendering. To stop the simulation, @@ -156,7 +156,7 @@ following: .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/00_sim/create_empty.py --viz none + python scripts/tutorials/00_sim/create_empty.py --viz none Now that we have a basic understanding of how to run a simulation, let's move on to the diff --git a/docs/source/tutorials/03_envs/create_manager_rl_env.rst b/docs/source/tutorials/03_envs/create_manager_rl_env.rst index a9afe1d73e09..f3bfc6faeced 100644 --- a/docs/source/tutorials/03_envs/create_manager_rl_env.rst +++ b/docs/source/tutorials/03_envs/create_manager_rl_env.rst @@ -163,7 +163,7 @@ Similar to the previous tutorial, we can run the environment by executing the `` .. code-block:: bash - ./isaaclab.sh -p scripts/tutorials/03_envs/run_cartpole_rl_env.py --num_envs 32 --viz kit + python scripts/tutorials/03_envs/run_cartpole_rl_env.py --num_envs 32 --viz kit This should open a similar simulation as in the previous tutorial. However, this time, the environment From b409ff597bbc4a1f44924f8ee42a30ae7f580f5a Mon Sep 17 00:00:00 2001 From: moennen Date: Mon, 8 Jun 2026 09:48:33 -0400 Subject: [PATCH 17/40] Make PPISP a peer IsaacLab extension dependency (#5986) # Description This PR fixes dependency resolution for non-camera Newton/PhysX/OV workflows by making isaaclab_ppisp a peer IsaacLab extension instead of a hard dependency of isaaclab_newton, isaaclab_physx, and isaaclab_ov. Previously, installing or resolving isaaclab-newton[all] could fail when isaaclab-ppisp was unavailable from the package registry, even for workloads that do not use camera ISP. This change keeps PPISP available through isaaclab[all], while renderer code imports it only when CameraCfg.isp_cfg is set. If PPISP is missing and ISP is requested, the renderer now raises an actionable install error. Dependencies required: none beyond existing IsaacLab extension dependencies. isaaclab_ppisp remains required only when using camera isp_cfg. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots Not applicable. ## Checklist - [x] I have read and understood the contribution guidelines (https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the pre-commit checks (https://pre-commit.com/) with ./isaaclab.sh --format - [ ] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's config/extension.toml file - [ ] I have added my name to the CONTRIBUTORS.md or my name already exists there --- .../nicolasm-ppisp-extension-dependency.rst | 4 +++ .../isaaclab/isaaclab/cli/commands/install.py | 4 +-- source/isaaclab/pyproject.toml | 1 + .../nicolasm-ppisp-extension-dependency.rst | 4 +++ source/isaaclab_newton/config/extension.toml | 1 - .../renderers/newton_warp_renderer.py | 28 ++++++++++++--- source/isaaclab_newton/pyproject.toml | 4 +-- .../nicolasm-ppisp-extension-dependency.rst | 4 +++ source/isaaclab_ov/config/extension.toml | 1 - .../isaaclab_ov/renderers/ovrtx_renderer.py | 36 ++++++++++++++----- source/isaaclab_ov/pyproject.toml | 4 +-- .../nicolasm-ppisp-extension-dependency.rst | 4 +++ source/isaaclab_physx/config/extension.toml | 1 - .../renderers/isaac_rtx_renderer.py | 35 ++++++++++++++---- source/isaaclab_physx/pyproject.toml | 4 +-- 15 files changed, 102 insertions(+), 33 deletions(-) create mode 100644 source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst create mode 100644 source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst create mode 100644 source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst create mode 100644 source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst diff --git a/source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst new file mode 100644 index 000000000000..a7d4ec21b507 --- /dev/null +++ b/source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed the ``isaaclab[all]`` extra to include ``isaaclab_ppisp`` as a peer extension. diff --git a/source/isaaclab/isaaclab/cli/commands/install.py b/source/isaaclab/isaaclab/cli/commands/install.py index f4d141dc4a08..d07571f17de1 100644 --- a/source/isaaclab/isaaclab/cli/commands/install.py +++ b/source/isaaclab/isaaclab/cli/commands/install.py @@ -466,8 +466,8 @@ def _install_isaacsim() -> None: # Source directories installed on every ./isaaclab.sh -i invocation (even "core"). # Order matters: isaaclab must be first so dependents resolve against the local copy, -# and isaaclab_ppisp must precede the renderer backends (newton/ov/physx) that -# declare it as an INSTALL_REQUIRES bare-name dep. +# and isaaclab_ppisp should precede renderer backends (newton/ov/physx) so local +# camera ISP support is available when CameraCfg.isp_cfg is used. CORE_ISAACLAB_SUBMODULES: list[str] = [ "isaaclab", "isaaclab_ppisp", diff --git a/source/isaaclab/pyproject.toml b/source/isaaclab/pyproject.toml index c9c7cbd4d64e..fe9296b5a721 100644 --- a/source/isaaclab/pyproject.toml +++ b/source/isaaclab/pyproject.toml @@ -92,6 +92,7 @@ all = [ "isaaclab_ov", "isaaclab_ovphysx", "isaaclab_physx[newton]", + "isaaclab_ppisp", "isaaclab_rl[all]", "isaaclab_tasks", "isaaclab_tasks_experimental", diff --git a/source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst new file mode 100644 index 000000000000..0715b7ffb75e --- /dev/null +++ b/source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed Newton package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index fefc0e5ce3f1..b87c4935290f 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -13,7 +13,6 @@ keywords = ["robotics", "simulation", "newton"] [dependencies] "isaaclab" = {} -"isaaclab_ppisp" = {} [core] reloadable = false diff --git a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py index 04745e894677..0fa0fe4db4b8 100644 --- a/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py +++ b/source/isaaclab_newton/isaaclab_newton/renderers/newton_warp_renderer.py @@ -9,7 +9,7 @@ import logging from dataclasses import dataclass -from typing import TYPE_CHECKING, Any +from typing import TYPE_CHECKING, Any, NoReturn import newton import torch @@ -31,6 +31,20 @@ logger = logging.getLogger(__name__) +_PPISP_IMPORT_ERROR_MESSAGE = ( + "isaaclab_ppisp is required when CameraCfg.isp_cfg is set. " + "Install Isaac Lab with the 'all' extra (`pip install isaaclab[all]`) or install the " + "isaaclab-ppisp extension from the Isaac Lab source checkout." +) + + +def _raise_missing_ppisp_error(exc: ModuleNotFoundError) -> NoReturn: + # Only translate missing isaaclab_ppisp imports into the optional-dependency hint; + # unrelated missing modules should surface unchanged for easier debugging. + if exc.name != "isaaclab_ppisp" and not (exc.name and exc.name.startswith("isaaclab_ppisp.")): + raise exc + raise ModuleNotFoundError(_PPISP_IMPORT_ERROR_MESSAGE, name="isaaclab_ppisp") from exc + class RenderData: # Back-compat alias for callers of ``RenderData.OutputNames``. @@ -68,10 +82,13 @@ def __init__(self, newton_sensor: newton.sensors.SensorTiledCamera, spec: Camera self.width = getattr(spec.cfg, "width", 100) self.height = getattr(spec.cfg, "height", 100) # Post-render PPISP pipeline composed when ``spec.cfg.isp_cfg`` is set. - # ``isp_cfg`` is already fully normalised by Camera by the time it reaches here. + # ``isp_cfg`` is already fully normalized by ``prepare_cameras`` by the time it reaches here. self.ppisp_pipeline: PpispPipeline | None = None if spec.cfg.isp_cfg is not None: - from isaaclab_ppisp import PpispPipeline + try: + from isaaclab_ppisp import PpispPipeline + except ModuleNotFoundError as exc: + _raise_missing_ppisp_error(exc) self.ppisp_pipeline = PpispPipeline(spec.cfg.isp_cfg) self._hdr_scratch_wp: wp.array | None = None @@ -263,7 +280,10 @@ def prepare_cameras(self, stage: Any, spec: CameraRenderSpec) -> None: """ if spec.cfg.isp_cfg is None or not spec.camera_prim_paths: return - from isaaclab_ppisp import resolve_and_normalize + try: + from isaaclab_ppisp import resolve_and_normalize + except ModuleNotFoundError as exc: + _raise_missing_ppisp_error(exc) spec.cfg.isp_cfg = resolve_and_normalize(spec.cfg.isp_cfg, stage, spec.camera_prim_paths[0]) diff --git a/source/isaaclab_newton/pyproject.toml b/source/isaaclab_newton/pyproject.toml index 300ae1baecef..8903ed7ed9e1 100644 --- a/source/isaaclab_newton/pyproject.toml +++ b/source/isaaclab_newton/pyproject.toml @@ -16,9 +16,7 @@ authors = [{name = "Isaac Lab Project Developers"}] maintainers = [{name = "Isaac Lab Project Developers"}] keywords = ["robotics", "simulation", "newton"] requires-python = ">=3.12" -dependencies = [ - "isaaclab_ppisp", -] +dependencies = [] [project.urls] Homepage = "https://github.com/isaac-sim/IsaacLab" diff --git a/source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst new file mode 100644 index 000000000000..45cef4e3fec5 --- /dev/null +++ b/source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed OVRTX package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index 476f0a33fd14..5254712507b7 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -9,4 +9,3 @@ keywords = ["robotics", "simulation", "rendering", "ovrtx", "omniverse"] [dependencies] "isaaclab" = {} -"isaaclab_ppisp" = {} diff --git a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py index bd724fdda4fc..bbf6012c54dc 100644 --- a/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py +++ b/source/isaaclab_ov/isaaclab_ov/renderers/ovrtx_renderer.py @@ -23,7 +23,7 @@ import math import os from pathlib import Path -from typing import TYPE_CHECKING, Any +from typing import TYPE_CHECKING, Any, NoReturn logger = logging.getLogger(__name__) @@ -86,6 +86,20 @@ RenderBufferKind.SIMPLE_SHADING_FULL_MDL.value: 3, } +_PPISP_IMPORT_ERROR_MESSAGE = ( + "isaaclab_ppisp is required when CameraCfg.isp_cfg is set. " + "Install Isaac Lab with the 'all' extra (`pip install isaaclab[all]`) or install the " + "isaaclab-ppisp extension from the Isaac Lab source checkout." +) + + +def _raise_missing_ppisp_error(exc: ModuleNotFoundError) -> NoReturn: + # Only translate missing isaaclab_ppisp imports into the optional-dependency hint; + # unrelated missing modules should surface unchanged for easier debugging. + if exc.name != "isaaclab_ppisp" and not (exc.name and exc.name.startswith("isaaclab_ppisp.")): + raise exc + raise ModuleNotFoundError(_PPISP_IMPORT_ERROR_MESSAGE, name="isaaclab_ppisp") from exc + def _resolve_rtx_minimal_mode(data_types: list[str]) -> int | None: """Resolve the RTX minimal mode from data types. @@ -129,10 +143,13 @@ def __init__(self, spec: CameraRenderSpec, device): self.num_rows = math.ceil(self.num_envs / self.num_cols) self.warp_buffers: dict[str, wp.array] = {} # Post-render PPISP pipeline composed when ``spec.cfg.isp_cfg`` is set. - # ``isp_cfg`` is already fully normalised by the time it reaches here (Camera does it). + # ``isp_cfg`` is already fully normalized by ``prepare_cameras`` by the time it reaches here. self.ppisp_pipeline: PpispPipeline | None = None if spec.cfg.isp_cfg is not None: - from isaaclab_ppisp import PpispPipeline + try: + from isaaclab_ppisp import PpispPipeline + except ModuleNotFoundError as exc: + _raise_missing_ppisp_error(exc) self.ppisp_pipeline = PpispPipeline(spec.cfg.isp_cfg) @@ -207,16 +224,19 @@ def __init__(self, cfg: OVRTXRendererCfg): def prepare_cameras(self, stage: Any, spec: CameraRenderSpec) -> None: """Resolve the camera's PPISP cfg and apply OVRTX-specific USD overrides. - First resolves ``spec.cfg.isp_cfg`` (sentinel discovery + normalization) - via :func:`isaaclab_ppisp.resolve_and_normalize` so :mod:`isaaclab` does - not need to know about PPISP. Then, when an ISP is configured, pins + When ``spec.cfg.isp_cfg`` is set, resolves it (sentinel discovery + + normalization) via :func:`isaaclab_ppisp.resolve_and_normalize` so + :mod:`isaaclab` does not need to know about PPISP. Then pins ``exposure:*`` to neutral and applies ``OmniRtxCameraExposureAPI_1`` so the RTX exposure model OVRTX embeds does not compound on top of the ISP. Without an ISP, the camera prim's authored exposure is left alone. """ - if not spec.camera_prim_paths: + if not spec.camera_prim_paths or spec.cfg.isp_cfg is None: return - from isaaclab_ppisp import apply_rtx_exposure_overrides, resolve_and_normalize + try: + from isaaclab_ppisp import apply_rtx_exposure_overrides, resolve_and_normalize + except ModuleNotFoundError as exc: + _raise_missing_ppisp_error(exc) spec.cfg.isp_cfg = resolve_and_normalize(spec.cfg.isp_cfg, stage, spec.camera_prim_paths[0]) if spec.cfg.isp_cfg is None: diff --git a/source/isaaclab_ov/pyproject.toml b/source/isaaclab_ov/pyproject.toml index 31a14bc0b13b..b9f686f8a3fe 100644 --- a/source/isaaclab_ov/pyproject.toml +++ b/source/isaaclab_ov/pyproject.toml @@ -16,9 +16,7 @@ authors = [{name = "Isaac Lab Project Developers"}] maintainers = [{name = "Isaac Lab Project Developers"}] keywords = ["robotics", "simulation", "rendering", "ovrtx", "omniverse"] requires-python = ">=3.12" -dependencies = [ - "isaaclab_ppisp", -] +dependencies = [] [project.urls] Homepage = "https://github.com/isaac-sim/IsaacLab" diff --git a/source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst new file mode 100644 index 000000000000..9b00c1c5d440 --- /dev/null +++ b/source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed Isaac RTX package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index f23036ec0893..785fb7b58567 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -13,7 +13,6 @@ keywords = ["robotics", "simulation", "physx"] [dependencies] "isaaclab" = {} -"isaaclab_ppisp" = {} [core] reloadable = false diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py index b770f50666ff..559ed744faf7 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/isaac_rtx_renderer.py @@ -11,7 +11,7 @@ import logging import math from dataclasses import dataclass, field -from typing import TYPE_CHECKING, Any +from typing import TYPE_CHECKING, Any, NoReturn import numpy as np import warp as wp @@ -38,6 +38,21 @@ from .isaac_rtx_renderer_cfg import IsaacRtxRendererCfg +_PPISP_IMPORT_ERROR_MESSAGE = ( + "isaaclab_ppisp is required when CameraCfg.isp_cfg is set. " + "Install Isaac Lab with the 'all' extra (`pip install isaaclab[all]`) or install the " + "isaaclab-ppisp extension from the Isaac Lab source checkout." +) + + +def _raise_missing_ppisp_error(exc: ModuleNotFoundError) -> NoReturn: + # Only translate missing isaaclab_ppisp imports into the optional-dependency hint; + # unrelated missing modules should surface unchanged for easier debugging. + if exc.name != "isaaclab_ppisp" and not (exc.name and exc.name.startswith("isaaclab_ppisp.")): + raise exc + raise ModuleNotFoundError(_PPISP_IMPORT_ERROR_MESSAGE, name="isaaclab_ppisp") from exc + + # RTX simple-shading constants. # # Simple shading is driven by Kit's RTX "Minimal" render mode via the @@ -106,16 +121,19 @@ def __init__(self, cfg: IsaacRtxRendererCfg): def prepare_cameras(self, stage: Any, spec: CameraRenderSpec) -> None: """Resolve the camera's PPISP cfg and apply RTX-specific USD overrides. - First resolves ``spec.cfg.isp_cfg`` (sentinel discovery + normalization) - via :func:`isaaclab_ppisp.resolve_and_normalize` so :mod:`isaaclab` does - not need to know about PPISP. Then, when an ISP is configured, pins + When ``spec.cfg.isp_cfg`` is set, resolves it (sentinel discovery + + normalization) via :func:`isaaclab_ppisp.resolve_and_normalize` so + :mod:`isaaclab` does not need to know about PPISP. Then pins ``exposure:*`` to neutral and applies ``OmniRtxCameraExposureAPI_1`` so RTX's physical-camera exposure model does not compound on top of the ISP. Without an ISP, the camera prim's authored exposure is left alone. """ - if not spec.camera_prim_paths: + if not spec.camera_prim_paths or spec.cfg.isp_cfg is None: return - from isaaclab_ppisp import apply_rtx_exposure_overrides, resolve_and_normalize + try: + from isaaclab_ppisp import apply_rtx_exposure_overrides, resolve_and_normalize + except ModuleNotFoundError as exc: + _raise_missing_ppisp_error(exc) spec.cfg.isp_cfg = resolve_and_normalize(spec.cfg.isp_cfg, stage, spec.camera_prim_paths[0]) if spec.cfg.isp_cfg is None: @@ -340,7 +358,10 @@ def create_render_data(self, spec: CameraRenderSpec) -> IsaacRtxRenderData: ppisp_pipeline = None if spec.cfg.isp_cfg is not None: - from isaaclab_ppisp import PpispPipeline + try: + from isaaclab_ppisp import PpispPipeline + except ModuleNotFoundError as exc: + _raise_missing_ppisp_error(exc) ppisp_pipeline = PpispPipeline(spec.cfg.isp_cfg, stage=stage) diff --git a/source/isaaclab_physx/pyproject.toml b/source/isaaclab_physx/pyproject.toml index 608074911f4e..c5b6ad86b9ed 100644 --- a/source/isaaclab_physx/pyproject.toml +++ b/source/isaaclab_physx/pyproject.toml @@ -16,9 +16,7 @@ authors = [{name = "Isaac Lab Project Developers"}] maintainers = [{name = "Isaac Lab Project Developers"}] keywords = ["robotics", "simulation", "physx"] requires-python = ">=3.12" -dependencies = [ - "isaaclab_ppisp", -] +dependencies = [] [project.urls] Homepage = "https://github.com/isaac-sim/IsaacLab" From 74f9e8ec73bef1ccd11819e3b5ef9fabb033dc35 Mon Sep 17 00:00:00 2001 From: lgulich <22480644+lgulich@users.noreply.github.com> Date: Mon, 8 Jun 2026 20:42:00 +0200 Subject: [PATCH 18/40] Fix LEAPP projected gravity export (#6007) ## Summary The current LEAPP export exports projected_gravity as an input instead of root_quat_w. The reason is that with the change to use warp for observation terms LEAPP can no longer automatically trace projected gravity back to root_quat_w. For new we fix this manually, once we have warp support in LEAPP this will no longer be needed. ## Changes - Export `mdp.projected_gravity` through `root_quat_w` for LEAPP graphs. - Keep the policy observation as projected gravity by computing it inside the exported graph. - Add regression coverage and a changelog fragment. ## Test Plan - `uv run --with pytest --with leapp python -m pytest source/isaaclab_rl/test/export/test_leapp_proxy.py -q` - `uv run --with ruff --with leapp ruff check source/isaaclab/isaaclab/utils/leapp/export_annotator.py source/isaaclab/isaaclab/utils/leapp/proxy.py source/isaaclab_rl/test/export/test_leapp_proxy.py` - `./isaaclab.sh -f` - Exported `Isaac-Velocity-Flat-G1-v0` checkpoint `model_1499.pt` and verified YAML uses `state/body/rotation` for `robot_root_quat_w`. --------- Co-authored-by: Claude Opus 4.8 --- .../lgulich-leapp-root-quat-gravity.rst | 6 + .../isaaclab/utils/leapp/export_annotator.py | 30 +++++ .../lgulich-leapp-root-quat-gravity.skip | 0 .../test/export/test_leapp_proxy.py | 104 ++++++++++++++++++ 4 files changed, 140 insertions(+) create mode 100644 source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst create mode 100644 source/isaaclab_rl/changelog.d/lgulich-leapp-root-quat-gravity.skip create mode 100644 source/isaaclab_rl/test/export/test_leapp_proxy.py diff --git a/source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst b/source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst new file mode 100644 index 000000000000..92af9a52251c --- /dev/null +++ b/source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed LEAPP export of :func:`isaaclab.envs.mdp.projected_gravity` to expose + root orientation as the graph input and compute projected gravity inside the + exported graph. diff --git a/source/isaaclab/isaaclab/utils/leapp/export_annotator.py b/source/isaaclab/isaaclab/utils/leapp/export_annotator.py index fb335811535a..3ca82a66c082 100644 --- a/source/isaaclab/isaaclab/utils/leapp/export_annotator.py +++ b/source/isaaclab/isaaclab/utils/leapp/export_annotator.py @@ -291,6 +291,8 @@ def _patch_observation_manager(self, obs_manager, proxy_env): term_cfg.func = self._wrap_last_action(original_func) elif func_name == "generated_commands": term_cfg.func = self._wrap_generated_commands(original_func, term_cfg) + elif func_name == "projected_gravity": + term_cfg.func = self._wrap_projected_gravity(original_func, proxy_env) else: term_cfg.func = self._wrap_with_proxy(original_func, proxy_env) @@ -445,6 +447,34 @@ def wrapped(*args, **kwargs): wrapped.__name__ = getattr(original_func, "__name__", "unknown") return wrapped + @staticmethod + def _wrap_projected_gravity(original_func, proxy_env): + """Wrap projected gravity as root-quaternion input plus fixed gravity projection. + + Deployment backends generally provide body orientation, not an already + projected gravity vector. During export, keep the policy observation as + projected gravity while exposing ``root_quat_w`` at the LEAPP graph + boundary. + """ + + def wrapped(*args, **kwargs): + """Compute projected gravity from an annotated root quaternion input.""" + kwargs.pop("inspect", None) + asset_cfg = kwargs.get("asset_cfg") + if asset_cfg is None and len(args) > 1: + asset_cfg = args[1] + asset_name = getattr(asset_cfg, "name", "robot") + root_quat_w = proxy_env.scene[asset_name].data.root_quat_w.torch + gravity_w = torch.zeros((*root_quat_w.shape[:-1], 3), dtype=root_quat_w.dtype, device=root_quat_w.device) + gravity_w[..., 2] = -1.0 + quat_xyz = root_quat_w[..., :3] + quat_w = root_quat_w[..., 3:4] + t = torch.cross(quat_xyz, gravity_w, dim=-1) * 2.0 + return gravity_w - quat_w * t + torch.cross(quat_xyz, t, dim=-1) + + wrapped.__name__ = getattr(original_func, "__name__", "unknown") + return wrapped + def _wrap_last_action(self, original_func): """Wrap ``last_action`` as a LEAPP state tensor. diff --git a/source/isaaclab_rl/changelog.d/lgulich-leapp-root-quat-gravity.skip b/source/isaaclab_rl/changelog.d/lgulich-leapp-root-quat-gravity.skip new file mode 100644 index 000000000000..e69de29bb2d1 diff --git a/source/isaaclab_rl/test/export/test_leapp_proxy.py b/source/isaaclab_rl/test/export/test_leapp_proxy.py new file mode 100644 index 000000000000..d57cbe1580b7 --- /dev/null +++ b/source/isaaclab_rl/test/export/test_leapp_proxy.py @@ -0,0 +1,104 @@ +# 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 + +import math +from types import SimpleNamespace + +import pytest +import torch + +pytest.importorskip("leapp") + +from isaaclab.envs import mdp +from isaaclab.test.mock_interfaces.assets.mock_articulation import MockArticulationData +from isaaclab.utils import math as math_utils +from isaaclab.utils.leapp import utils as leapp_utils +from isaaclab.utils.leapp.export_annotator import ExportPatcher +from isaaclab.utils.leapp.leapp_semantics import InputKindEnum +from isaaclab.utils.leapp.proxy import _DataProxy, _EnvProxy + + +class _TestScene(dict): + """Minimal scene mapping for LEAPP proxy tests.""" + + sensors = {} + + +def _make_articulation_data() -> tuple[MockArticulationData, torch.Tensor]: + """Create mock articulation data with a non-identity root orientation.""" + data = MockArticulationData(num_instances=2, num_joints=0, num_bodies=1, device="cpu") + root_pose_w = torch.zeros(2, 7, dtype=torch.float32) + root_pose_w[:, 6] = 1.0 + root_pose_w[1, 3] = math.sin(math.pi / 4.0) + root_pose_w[1, 6] = math.cos(math.pi / 4.0) + data.set_root_link_pose_w(root_pose_w) + return data, root_pose_w + + +def _capture_leapp_inputs(monkeypatch: pytest.MonkeyPatch) -> list: + """Capture LEAPP input annotations while returning their tensor references.""" + annotated_inputs = [] + + def _record_input_tensor(task_name, semantics): + annotated_inputs.append((task_name, semantics)) + return semantics.ref + + monkeypatch.setattr(leapp_utils.annotate, "input_tensors", _record_input_tensor) + return annotated_inputs + + +def test_direct_projected_gravity_b_read_preserves_vector3d_input(monkeypatch: pytest.MonkeyPatch): + """Test direct data proxy reads keep projected gravity as its own semantic input.""" + annotated_inputs = _capture_leapp_inputs(monkeypatch) + data, _ = _make_articulation_data() + + proxy = _DataProxy( + data, + entity_name="robot", + task_name="Isaac-Velocity-Flat-G1-v0", + property_resolution_cache={}, + cache={}, + input_name_resolver=lambda property_name: f"robot_{property_name}", + ) + + assert proxy.projected_gravity_b.torch.shape == (2, 3) + + assert len(annotated_inputs) == 1 + task_name, semantics = annotated_inputs[0] + assert task_name == "Isaac-Velocity-Flat-G1-v0" + assert semantics.name == "robot_projected_gravity_b" + assert semantics.kind == InputKindEnum.VECTOR3D + assert semantics.extra == {"isaaclab_connection": "state:robot:projected_gravity_b"} + + +def test_projected_gravity_observation_exports_root_quat_w_input(monkeypatch: pytest.MonkeyPatch): + """Test the projected-gravity observation is export-lowered through root quaternion.""" + annotated_inputs = _capture_leapp_inputs(monkeypatch) + data, root_pose_w = _make_articulation_data() + scene = _TestScene({"robot": SimpleNamespace(data=data)}) + env = SimpleNamespace(scene=scene) + proxy_env = _EnvProxy(env, "Isaac-Velocity-Flat-G1-v0", {}, {}) + + term_cfg = SimpleNamespace(func=mdp.projected_gravity, noise="noise") + obs_manager = SimpleNamespace(_group_obs_term_cfgs={"policy": [term_cfg]}, compute=lambda *args, **kwargs: None) + patcher = ExportPatcher(export_method="onnx-dynamo", required_obs_groups={"policy"}) + patcher.task_name = "Isaac-Velocity-Flat-G1-v0" + patcher._patch_observation_manager(obs_manager, proxy_env) + + projected_gravity_b = term_cfg.func(env) + + expected = math_utils.quat_apply_inverse( + root_pose_w[:, 3:7], + torch.tensor([[0.0, 0.0, -1.0]], dtype=torch.float32).expand(2, 3), + ) + assert torch.allclose(projected_gravity_b, expected) + assert term_cfg.noise is None + + assert len(annotated_inputs) == 1 + task_name, semantics = annotated_inputs[0] + assert task_name == "Isaac-Velocity-Flat-G1-v0" + assert semantics.name == "robot_root_quat_w" + assert semantics.kind == InputKindEnum.BODY_ROTATION + assert semantics.extra == {"isaaclab_connection": "state:robot:root_quat_w"} From ef68a5ec817a0aaac14f534a76659b66da56771d Mon Sep 17 00:00:00 2001 From: Piotr Barejko Date: Mon, 8 Jun 2026 12:42:40 -0700 Subject: [PATCH 19/40] Make env* functions thread safe through carb env shim layer (#5735) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Please include a summary of the change and which issue is fixed. Please also include relevant motivation and context. List any dependencies that are required for this change. Fixes # (issue) ## Type of change - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) - Breaking change (existing functionality will not work without user modification) - Documentation update ## Screenshots Please attach before and after screenshots of the change if applicable. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docker/Dockerfile.base | 37 +++++++++++++++++++ .../changelog.d/pbarejko-carb-env-shim.skip | 7 ++++ 2 files changed, 44 insertions(+) create mode 100644 source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip diff --git a/docker/Dockerfile.base b/docker/Dockerfile.base index 6c893fd8cbea..a8c6a0066311 100644 --- a/docker/Dockerfile.base +++ b/docker/Dockerfile.base @@ -49,6 +49,43 @@ RUN apt-get update && \ git \ wget +# Install the Carbonite env shim (libcarb.env.shim.so) that serializes glibc's +# environment functions (getenv/setenv/putenv/unsetenv/secure_getenv/clearenv). +# Carb/Kit/Omni plugins call these from worker threads while other threads +# mutate the environment, which intermittently crashes CI with +# `libc.so.6!getenv+0x56` SIGSEGVs. The shim now ships inside Isaac Sim's +# Carbonite, so we copy it out of the install tree rather than vendoring a +# prebuilt binary. +# +# Activation uses /etc/ld.so.preload (not ENV LD_PRELOAD) because Isaac Sim's +# `_isaac_sim/python.sh` unconditionally overwrites LD_PRELOAD with +# `kit/libcarb.so` before exec'ing the interpreter, which would strip our +# shim. /etc/ld.so.preload is read by the dynamic linker for every process +# and cannot be turned off by env-var manipulation. +RUN install_carb_env_shim() { \ + local dst=/usr/local/lib/libcarb.env.shim.so; \ + local src=""; \ + for c in \ + "${ISAACSIM_ROOT_PATH}/kit/kernel/plugins/libcarb.env.shim.so" \ + "${ISAACSIM_ROOT_PATH}/kit/libcarb.env.shim.so" \ + "${ISAACSIM_ROOT_PATH}/_build/linux-x86_64/release/kit/kernel/plugins/libcarb.env.shim.so" \ + "${ISAACSIM_ROOT_PATH}/_build/target-deps/carb_sdk_plugins/_build/linux-x86_64/release/libcarb.env.shim.so" \ + ; do \ + if [ -f "${c}" ]; then src="${c}"; break; fi; \ + done; \ + if [ -z "${src}" ]; then \ + src="$(find "${ISAACSIM_ROOT_PATH}" -name libcarb.env.shim.so -type f 2>/dev/null | head -n1)"; \ + fi; \ + if [ -n "${src}" ] && [ -f "${src}" ]; then \ + install -m 0755 "${src}" "${dst}" && \ + echo "${dst}" > /etc/ld.so.preload && \ + echo "installed carb env shim from ${src}"; \ + else \ + echo "no carb env shim found under ${ISAACSIM_ROOT_PATH}; skipping /etc/ld.so.preload" >&2; \ + fi; \ + }; \ + install_carb_env_shim + # arm64-only build deps: # - imgui-bundle has no prebuilt arm64 wheel; needs GL/X11 dev headers. # - swig is required for the nlopt source build (see arm64 nlopt step below). diff --git a/source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip b/source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip new file mode 100644 index 000000000000..3e85fdd60bc6 --- /dev/null +++ b/source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip @@ -0,0 +1,7 @@ +Fixed +^^^^^ + +* Fixed intermittent ``getenv`` SIGSEGVs in Docker CI by copying the + Carbonite ``libcarb.env.shim.so`` out of the Isaac Sim install tree and + preloading it via ``/etc/ld.so.preload`` at image-build time, instead of + vendoring a prebuilt shim binary in the repo. From bde6e2d91bc0711945263d46f26edf1f41208ea7 Mon Sep 17 00:00:00 2001 From: ooctipus Date: Mon, 8 Jun 2026 14:34:02 -0700 Subject: [PATCH 20/40] Fix quadruped tutorial noise import (#6033) ## Summary - Update the quadruped base tutorial to import UniformNoiseCfg, which is the current noise config API used elsewhere in the repo. - Preserve behavior: UniformNoiseCfg defaults to additive noise, matching the tutorial usage. ## Validation - python3 -m py_compile scripts/tutorials/03_envs/create_quadruped_base_env.py - pre-commit run --files scripts/tutorials/03_envs/create_quadruped_base_env.py - python3 tools/changelog/cli.py check develop Full Kit launch was not run locally; this environment does not have the prepared Isaac Lab runtime dependencies installed. --- scripts/tutorials/03_envs/create_quadruped_base_env.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/tutorials/03_envs/create_quadruped_base_env.py b/scripts/tutorials/03_envs/create_quadruped_base_env.py index 8f287b5005ff..26cce6250a8d 100644 --- a/scripts/tutorials/03_envs/create_quadruped_base_env.py +++ b/scripts/tutorials/03_envs/create_quadruped_base_env.py @@ -54,7 +54,7 @@ from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR, check_file_path, read_file from isaaclab.utils.configclass import configclass -from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise +from isaaclab.utils.noise import UniformNoiseCfg as Unoise ## # Pre-defined configs From 4a7323e59020d25daf84df9052f11d8a95767fdc Mon Sep 17 00:00:00 2001 From: ooctipus Date: Mon, 8 Jun 2026 17:39:43 -0700 Subject: [PATCH 21/40] Fix MDL module dependency retrieval (#6034) ## Summary - Collect relative MDL module imports when mirroring remote assets locally. - Covers ordinary `import` and `[export] using ... import ...` forms, including current-package `.::` imports and parent-package `..::` imports. - Leaves global/built-in MDL modules to the renderer module path while preserving existing MDL texture dependency handling. ## Validation - `python3 -m py_compile source/isaaclab/isaaclab/utils/assets.py source/isaaclab/test/utils/test_assets.py` - direct importlib check for `_find_mdl_dependencies` with Hospital-style relative imports, using-imports, and parent-relative imports - `python3 tools/changelog/cli.py check develop` - `pre-commit run --files source/isaaclab/isaaclab/utils/assets.py source/isaaclab/test/utils/test_assets.py source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst` Focused pytest was not runnable in this shell because the local Python environment is missing `lazy_loader`. Full Kit/Hospital viewport repro was not run locally. --- .../fix-mdl-module-dependencies.rst | 4 ++ source/isaaclab/isaaclab/utils/assets.py | 58 ++++++++++++++++--- source/isaaclab/test/utils/test_assets.py | 35 +++++++++++ 3 files changed, 89 insertions(+), 8 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst diff --git a/source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst b/source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst new file mode 100644 index 000000000000..930fd7b83a69 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed local asset retrieval for MDL files that import sibling MDL modules, such as Hospital materials importing OmniUe4 modules. diff --git a/source/isaaclab/isaaclab/utils/assets.py b/source/isaaclab/isaaclab/utils/assets.py index 603df8b2aa43..4e30f2f275c6 100644 --- a/source/isaaclab/isaaclab/utils/assets.py +++ b/source/isaaclab/isaaclab/utils/assets.py @@ -28,6 +28,11 @@ _USD_EXTENSIONS = {".usd", ".usda", ".usdc", ".usdz"} _MDL_RESOURCE_RE = re.compile(r'"([^"\\]*(?:\\.[^"\\]*)*)"|/\*.*?\*/|//[^\r\n]*', re.DOTALL) _MDL_TEXTURE_RE = re.compile(r"\.(?:bmp|dds|exr|hdr|ies|jpe?g|ktx2?|png|tga|tiff?|tx)(?:[?#].*)?$", re.IGNORECASE) +_MDL_IMPORT_RE = re.compile(r"\bimport\s+([^;]+);") +_MDL_USING_IMPORT_RE = re.compile(r"\busing\s+(.+?)\s+import\s+[^;]+;") +_MDL_RELATIVE_IMPORT_RE = re.compile( + r"(?P(?:\.\.::)+|\.::)(?P[A-Za-z_]\w*(?:::[A-Za-z_]\w*)*)(?P::\*)?" +) def _parse_kit_asset_root() -> str: @@ -198,8 +203,8 @@ def _find_asset_dependencies(local_asset_path: str) -> set[str]: """Collect external asset dependencies from a local asset file. USD layers are parsed with OpenUSD. MDL files are scanned for quoted texture - resources because those references are resolved later by the MDL compiler and - are not reported by USD dependency discovery. + resources and relative module imports because those references are resolved + later by the MDL compiler and are not reported by USD dependency discovery. """ suffix = os.path.splitext(local_asset_path)[1].lower() @@ -211,12 +216,7 @@ def _find_asset_dependencies(local_asset_path: str) -> set[str]: logger.warning("Failed to open MDL file: %s (%s)", local_asset_path, e) return set() - refs = set() - for match in _MDL_RESOURCE_RE.finditer(source): - ref = match.group(1) - if ref and _MDL_TEXTURE_RE.search(ref.strip()): - refs.add(ref.strip()) - return refs + return _find_mdl_dependencies(source) if suffix not in _USD_EXTENSIONS: return set() @@ -244,6 +244,48 @@ def _collect(path: str) -> str: return refs +def _find_mdl_dependencies(source: str) -> set[str]: + """Collect local asset dependencies from MDL source text.""" + refs = set() + + for match in _MDL_RESOURCE_RE.finditer(source): + ref = match.group(1) + if ref and _MDL_TEXTURE_RE.search(ref.strip()): + refs.add(ref.strip()) + + source_code = _MDL_RESOURCE_RE.sub("", source) + for match in _MDL_USING_IMPORT_RE.finditer(source_code): + refs.update(_find_mdl_import_dependencies(match.group(1))) + source_code = _MDL_USING_IMPORT_RE.sub("", source_code) + for match in _MDL_IMPORT_RE.finditer(source_code): + refs.update(_find_mdl_import_dependencies(match.group(1))) + + return refs + + +def _find_mdl_import_dependencies(import_clause: str) -> set[str]: + """Collect local MDL modules referenced by an import clause.""" + refs = set() + + for match in _MDL_RELATIVE_IMPORT_RE.finditer(import_clause): + prefix = match.group("prefix") + package_prefix = [".."] * prefix.count("..::") + components = [component for component in match.group("module").split("::") if component] + if not components: + continue + + if match.group("wildcard") is not None: + candidate_lengths = (len(components),) + else: + # ``import .::A::B;`` can mean module ``A::B`` or symbol ``B`` from module ``A``. + candidate_lengths = range(1, len(components) + 1) + + for length in candidate_lengths: + refs.add(posixpath.join(*(package_prefix + components[:length])) + ".mdl") + + return refs + + def _resolve_reference_url(base_url: str, ref: str) -> str: """Resolve a USD asset reference against a base URL (http/local).""" ref = ref.strip() diff --git a/source/isaaclab/test/utils/test_assets.py b/source/isaaclab/test/utils/test_assets.py index d4019246e637..ab13a9a7c772 100644 --- a/source/isaaclab/test/utils/test_assets.py +++ b/source/isaaclab/test/utils/test_assets.py @@ -58,6 +58,41 @@ def test_find_asset_dependencies_collects_mdl_texture_resources(tmp_path): } +def test_find_asset_dependencies_collects_mdl_relative_import_modules(tmp_path): + """Test collecting sibling MDL modules imported by material files.""" + mdl_path = tmp_path / "material.mdl" + mdl_path.write_text( + """ + import .::OmniUe4Function; + import .::OmniUe4Translucent::*; + import .::Shared::OmniUe4Base::*; + import .::Helpers::make_color; + import ..::Common::Surface::*; + export using .::Local::Palette import *; + using ..::Shared::Functions import make_color, make_normal; + import ::nvidia::core_definitions::*; + export material Example(*) = OmniPBR(); + // import .::CommentedLine; + /* import .::CommentedBlock; */ + string ignored = "import .::QuotedString;"; + """, + encoding="utf-8", + ) + + assert assets_utils._find_asset_dependencies(str(mdl_path)) == { + "OmniUe4Function.mdl", + "OmniUe4Translucent.mdl", + "Shared/OmniUe4Base.mdl", + "Helpers.mdl", + "Helpers/make_color.mdl", + "../Common/Surface.mdl", + "Local.mdl", + "Local/Palette.mdl", + "../Shared.mdl", + "../Shared/Functions.mdl", + } + + def test_find_asset_dependencies_missing_mdl_does_not_log_traceback(tmp_path, caplog): """Test unavailable MDL dependencies do not emit tracebacks in training logs.""" missing_mdl = tmp_path / "missing.mdl" From 280e86edfe7d5ae062a197564a473c6b5a217859 Mon Sep 17 00:00:00 2001 From: sameerchavan0027 Date: Mon, 8 Jun 2026 17:41:13 -0700 Subject: [PATCH 22/40] Update COMPASS training doc (#6030) # Description Move compass training tutorial doc to COMPASS repo --- .../compass_navigation_policy_with_NuRec.rst | 549 +----------------- 1 file changed, 14 insertions(+), 535 deletions(-) diff --git a/docs/source/policy_deployment/03_compass_with_NuRec/compass_navigation_policy_with_NuRec.rst b/docs/source/policy_deployment/03_compass_with_NuRec/compass_navigation_policy_with_NuRec.rst index 58341f070deb..0f11d31bc7fd 100644 --- a/docs/source/policy_deployment/03_compass_with_NuRec/compass_navigation_policy_with_NuRec.rst +++ b/docs/source/policy_deployment/03_compass_with_NuRec/compass_navigation_policy_with_NuRec.rst @@ -1,548 +1,27 @@ Training & Deploying COMPASS Navigation Policy with Real2Sim NuRec ==================================================================== -This tutorial shows you how to train and deploy COMPASS navigation policies using NuRec Real2Sim assets in the Isaac Lab simulation environment. -COMPASS (Cross-embodiment Mobility Policy via Residual RL and Skill Synthesis) is a novel framework for cross-embodiment mobility. -For more details about the project, please visit the `COMPASS Repository`_. +COMPASS (Cross-embodiment Mobility Policy via Residual RL and Skill Synthesis) trains and +deploys cross-embodiment navigation policies on NuRec Real2Sim assets — photoreal +Gaussian-splat reconstructions of real spaces — in Isaac Lab. -Workflow Overview ------------------ +This tutorial now lives in the **COMPASS handbook**, next to the code it documents, where it +stays in sync with the NuRec support branch. -The following provides a high-level overview of the complete workflow: +Where to find it +---------------- -1. **Create workspace**: Create the ``compass-nurec`` workspace directory -2. **Install Isaac Sim & Isaac Lab** (Terminal 1): Follow installation steps for Isaac Sim 6.0 and Isaac Lab 3.0 -3. **Install COMPASS Repository** (Terminal 2): Clone and set up the COMPASS repository -4. **Authenticate with Hugging Face**: Generate access token and run ``hf auth login --token `` -5. **Download assets** (can be done in parallel): - - - Download X-Mobility checkpoint: ``hf download nvidia/X-Mobility x_mobility-nav2-semantic_action_path.ckpt`` - - Download COMPASS USD assets: ``hf download nvidia/COMPASS compass_usds.zip`` - - Download NuRec Real2Sim assets: ``hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset`` - -6. **Prepare assets**: - - - Extract and place ``usd/`` folder into ``compass/rl_env/exts/mobility_es/mobility_es/`` - - Place environment files (e.g., ``nova_carter-galileo/``) in the appropriate location -7. **Test setup**: Verify installation using ``play.py`` -8. **Train Residual RL Policy**: Run training with ``run.py`` and ``train_config_real2sim.gin`` -9. **Evaluate Trained Policy**: Run evaluation with ``run.py`` and ``eval_config_real2sim.gin`` -10. **Export to ONNX / TensorRT**: Convert the trained model for deployment -11. **ROS2 Deployment / Sim-to-Real Transfer**: Deploy the policy for real-world use - -Setup ------ - -.. note:: - - This tutorial is for **Ubuntu 22.04** and the **OVX with RTX platform**. It is intended for Isaac Lab 3.0.0 and Isaac Sim 6.0.0. - -Create a Workspace -~~~~~~~~~~~~~~~~~~ - -Start by creating a dedicated workspace directory for this project: - -.. code-block:: bash - - mkdir compass-nurec - cd compass-nurec - -Terminal 1 — Isaac Lab & Isaac Sim Installation -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Follow these steps in your first terminal to install Isaac Sim and Isaac Lab. - -1. Install Isaac Sim 6.0. The supported installation methods are: - - - **pip install** (recommended): Follow the `Isaac Sim pip Installation Guide`_. - - **Binary download**: Download the pre-built binary from the `Isaac Sim Installation Guide`_. - -2. Clone the Isaac Lab repository and check out the latest release branch: - -.. isaaclab-clone-https:: - -3. Set the required environment variables: - -.. note:: - - This step is only required if Isaac Sim was installed via the **binary download**. - If you installed Isaac Sim via ``pip``, these variables are not needed. - -.. code-block:: bash - - # Isaac Sim root directory - export ISAACSIM_PATH="${HOME}/isaacsim" - - # Isaac Sim python executable - export ISAACSIM_PYTHON_EXE="${ISAACSIM_PATH}/python.sh" - -4. Verify that Isaac Sim starts correctly: - -.. code-block:: bash - - ${ISAACSIM_PATH}/isaac-sim.sh - -5. Create a symbolic link to Isaac Sim inside the Isaac Lab directory: - -.. code-block:: bash - - ln -s ${ISAACSIM_PATH} _isaac_sim - -6. Create a dedicated conda environment and install Isaac Lab: - -.. code-block:: bash - - # Create the conda environment - ./isaaclab.sh --conda env_isaaclab_3.0_compass - - # Activate the environment - conda activate env_isaaclab_3.0_compass - - # Install Isaac Lab - ./isaaclab.sh --install - -7. Verify the Isaac Lab installation: - -.. code-block:: bash - - ./isaaclab.sh -p scripts/tutorials/00_sim/create_empty.py --visualizer kit - -Terminal 2 — COMPASS Installation -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Open a second terminal and follow these steps to install the COMPASS repository. - -1. Activate the conda environment created in Terminal 1: - -.. code-block:: bash - - conda deactivate - conda activate env_isaaclab_3.0_compass - -2. Clone the COMPASS repository and check out the NuRec-compatible branch: +- **Repository:** `COMPASS on GitHub `_ +- **Branch:** ``samc/support_nurec_assets_isaaclab_3.0`` (NuRec Real2Sim support) +- **Guide:** `docs/handbook/workflows/nurec_real2sim.md `_ in the COMPASS repository. .. code-block:: bash git clone https://github.com/NVlabs/COMPASS.git cd COMPASS - git fetch git checkout samc/support_nurec_assets_isaaclab_3.0 + # Open docs/handbook/workflows/nurec_real2sim.md -3. Set the path to your Isaac Lab installation: - -.. code-block:: bash - - export ISAACLAB_PATH= - -4. Install the Python dependencies: - -.. code-block:: bash - - ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -r requirements.txt - -5. Install the X-Mobility base policy package: - -.. code-block:: bash - - ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install x_mobility/x_mobility-0.1.0-py3-none-any.whl - -6. Install the ``mobility_es`` Isaac Lab extension: - -.. code-block:: bash - - cd compass/rl_env - ${ISAACLAB_PATH}/isaaclab.sh -p -m pip install -e exts/mobility_es - cd - - -Downloading Assets & Checkpoints -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Authentication -^^^^^^^^^^^^^^ - -Before downloading assets, you need to authenticate with Hugging Face. Follow the `Hugging Face security tokens documentation`_ to generate a Hugging Face access token. - -Once you have generated your access token, authenticate using: - -.. code-block:: bash - - hf auth login --token - -**1. Pre-trained X-Mobility checkpoint** - -Download the checkpoint using the Hugging Face CLI: - -.. code-block:: bash - - hf download nvidia/X-Mobility x_mobility-nav2-semantic_action_path.ckpt --local-dir /X-Mobility - -Alternatively, you can download it manually from: -https://huggingface.co/nvidia/X-Mobility/blob/main/x_mobility-nav2-semantic_action_path.ckpt - -**2. COMPASS USD Assets** - -Download the pre-packaged COMPASS USD assets using the Hugging Face CLI: - -.. code-block:: bash - - hf download nvidia/COMPASS compass_usds.zip --local-dir /COMPASS - -Alternatively, you can download it manually from: -https://huggingface.co/nvidia/COMPASS/blob/main/compass_usds.zip - -Extract the downloaded ``compass_usds.zip`` file and move the ``usd`` folder into the COMPASS extension directory: - -.. code-block:: bash - - cd /COMPASS - unzip compass_usds.zip - mv groot_mobility_rl_es_usds/usd compass/rl_env/exts/mobility_es/mobility_es/ - -**3. NuRec Real2Sim Assets** - -Download the NuRec Real2Sim assets from the `PhysicalAI-Robotics-NuRec dataset`_ on Hugging Face using the Hugging Face CLI: - -.. code-block:: bash - - hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset --local-dir /PhysicalAI-Robotics-NuRec - -.. tip:: - - The full dataset is large. To download only the environment(s) you need, use the ``--include`` and - ``--exclude`` glob filters supported by ``hf download``. Quote the patterns so your shell does not - expand them, and the original folder structure is preserved under ``--local-dir``. - - .. code-block:: bash - - # Download a single environment - hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset \ - --local-dir /PhysicalAI-Robotics-NuRec \ - --include "nova_carter-galileo/*" - - # Download multiple environments at once - hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset \ - --local-dir /PhysicalAI-Robotics-NuRec \ - --include "nova_carter-galileo/*" "nova_carter-cafe/*" - - # Recursively include sub-folders - hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset \ - --local-dir /PhysicalAI-Robotics-NuRec \ - --include "nova_carter-galileo/**" - - # Pull only specific files within an environment - hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset \ - --local-dir /PhysicalAI-Robotics-NuRec \ - --include "nova_carter-galileo/stage.usdz" "nova_carter-galileo/3dgrt/**" - - # Download everything except the large mesh files - hf download nvidia/PhysicalAI-Robotics-NuRec --repo-type dataset \ - --local-dir /PhysicalAI-Robotics-NuRec \ - --exclude "**/*.usdz" - -Alternatively, you can download them manually from the `PhysicalAI-Robotics-NuRec dataset`_ on Hugging Face: - -.. note:: - - You need to agree to the dataset terms on Hugging Face before accessing the files. - -The dataset provides several environments. For COMPASS, download the environment(s) you need -(e.g., ``nova_carter-galileo``) and place the extracted files under the COMPASS extension directory: - -.. code-block:: bash - - # Ensure that you are in COMPASS root directory - compass/rl_env/exts/mobility_es/mobility_es/usd// - -For example, for the Galileo environment (nova_carter-galileo), move the downloaded folder into -the COMPASS extension directory: - -.. code-block:: bash - - # Run from the COMPASS root directory - mv /PhysicalAI-Robotics-NuRec/nova_carter-galileo \ - compass/rl_env/exts/mobility_es/mobility_es/usd/ - -The resulting layout should look like: - -.. code-block:: bash - - compass/rl_env/exts/mobility_es/mobility_es/usd/nova_carter-galileo/ - ├── stage.usdz - ├── occupancy_map.yaml - ├── occupancy_map.png - └── 3dgrt - ├── last.usdz - ├── real2sim_galileo.usd - └── omap - ├── occupancy_map.yaml - └── occupancy_map.png - -.. note:: - - The following are the available COMPASS compatible scenes from the NuRec dataset: - - .. list-table:: - :header-rows: 1 - :widths: 30 50 20 - - * - Environment Name - - Description - - Contains Mesh - * - ``nova_carter-galileo`` - - Galileo lab in NVIDIA — aisles, shelves, and boxes - - Yes - * - ``nova_carter-cafe`` - - NVIDIA cafe — open area with natural lighting - - Yes - * - ``nova_carter-wormhole`` - - Conference room some chairs and tables - - Yes - * - ``hand_hold-endeavor-livingroom`` - - Living room in NVIDIA Endeavor building - - Yes - * - ``hand_hold-endeavor-andoria`` - - Meeting room in NVIDIA Endeavor building - - Yes - * - ``hand_hold-endeavor-wormhole`` - - Conference room in NVIDIA Endeavor building - - Yes - * - ``hand_hold-voyager-babyboom-2`` - - Conference room in NVIDIA Voyager building - - Yes - -Testing the Setup -~~~~~~~~~~~~~~~~~ - -Once the COMPASS USD assets have been downloaded and placed under -``compass/rl_env/exts/mobility_es/mobility_es/usd/``, run the following command from the ``COMPASS`` -directory to verify the setup: - -.. code-block:: bash - - cd compass/rl_env - ${ISAACLAB_PATH}/isaaclab.sh -p scripts/play.py --enable_cameras --visualizer kit - cd - - -Training the Policy -------------------- - -Training Configuration -~~~~~~~~~~~~~~~~~~~~~~ - -The training configuration for NuRec Real2Sim environments is specified in ``configs/train_config_real2sim.gin``. -This configuration includes optimized settings for Real2Sim environments: - -- **Collision checking distances**: Tuned for Real2Sim environments (0.5m for both goal and start poses) -- **Precomputed valid poses**: Enabled for faster pose sampling in constrained environments -- **compute_orientations**: Set to True to compute orientations for the start and goal poses. -- **Environment spacing**: Set to 500m to accommodate larger Real2Sim scenes - -Training the Residual RL Specialist -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Execute the following command from the ``COMPASS`` directory (Terminal 2) to train a residual RL specialist policy for NuRec Real2Sim environments. - -.. code-block:: bash - - ${ISAACLAB_PATH:?}/isaaclab.sh -p run.py \ - -c configs/train_config_real2sim.gin \ - -o \ - -b \ - --embodiment \ - --environment nova_carter-galileo \ - --num_envs 64 \ - --video \ - --video_interval 1 \ - --visualizer kit \ - --enable_cameras \ - --precompute_valid_poses - -.. note:: - - To run in headless mode, either omit the ``--visualizer kit`` flag or specify ``--visualizer None``. - -Where: - -- ````: Directory where training outputs and checkpoints will be saved -- ````: Path to the downloaded X-Mobility checkpoint -- ````: One of ``h1``, ``spot``, ``carter``, ``g1``, or ``digit`` -- ``--environment nova_carter-galileo``: Specifies the NuRec Real2Sim Galileo environment - -The training will run for the number of iterations specified in the config file (default: 1000 iterations). -Checkpoints are saved directly under ``/`` with the filename ``model_.pt`` (e.g., ``model_0.pt``, ``model_50.pt``, ``model_100.pt``), written every 50 iterations. -Videos will be saved in ``/videos/``. - -.. note:: - - GPU memory scales approximately linearly with ``--num_envs``. With NuRec Real2Sim assets, - the per-environment cost is roughly **2× higher** than the default COMPASS training scene - (heavier USDs). - - Empirical fit measured on an RTX A6000 (Carter + ``nova_carter-galileo``): - - .. code-block:: text - - VRAM ≈ 9 GB (fixed) + 1.3 GB × num_envs - - Rough safe ``--num_envs`` ceiling (with ~15% headroom for allocator and PPO update spikes): - - =================== ======== ========================= - GPU VRAM Safe ``--num_envs`` (NuRec) - =================== ======== ========================= - RTX 5090 32 GB ~14 - RTX A6000 / L40 48 GB ~24 - =================== ======== ========================= - - Reduce ``--num_envs`` if you hit OOM, or lower the camera resolution in - ``scene_assets.camera`` to shrink the per-env cost. - - For Real2Sim environments, it's recommended to use ``--precompute_valid_poses`` flag to precompute valid pose locations, - which significantly speeds up pose sampling in constrained environments. - For very tight spaces, it's recommended to use ``--compute_orientations`` flag to compute orientations for the start and goal poses. - Orientation computation is slow so use it only if necessary. - -Advanced Training Options -~~~~~~~~~~~~~~~~~~~~~~~~~ - -You can customize the training by modifying the gin config file or using command-line arguments: - -- **Collision distances**: Adjust ``goal_pose_collision_distance`` and ``start_pose_collision_distance`` in the config -- **Precompute valid poses**: Set ``precompute_valid_poses = True`` in the config or use ``--precompute_valid_poses`` flag -- **Compute orientations**: Set ``compute_orientations = True`` in the config or use ``--compute_orientations`` flag -- **Number of iterations**: Modify ``num_iterations`` in the config -- **Number of environments**: Use ``--num_envs`` command-line argument - -Testing the Trained Policy --------------------------- - -Evaluate the trained policy -~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Execute the following command from the ``COMPASS`` directory to evaluate the trained policy checkpoint. - -.. code-block:: bash - - ${ISAACLAB_PATH:?}/isaaclab.sh -p run.py \ - -c configs/eval_config_real2sim.gin \ - -o \ - -b \ - -p \ - --embodiment \ - --environment nova_carter-galileo \ - --num_envs \ - --video \ - --video_interval 1 \ - --enable_cameras \ - --visualizer kit - -.. note:: - - To run in headless mode, either omit the ``--visualizer kit`` flag or specify ``--visualizer None``. - -Where: - -- ````: Path to the trained residual policy checkpoint (e.g., ``/model_1000.pt``) -- ``--video``: Enable video recording during evaluation -- ``--video_interval``: Record video every N iterations - -The evaluation will run for the number of iterations specified in the eval config file. -Videos will be saved in ``/videos/``. - -Model Export ------------- - -Export to ONNX or JIT -~~~~~~~~~~~~~~~~~~~~~ - -Export the trained residual RL specialist policy to ONNX or JIT formats for deployment. - -.. code-block:: bash - - # : training output directory, : root of the cloned COMPASS repo - cd / - python3 /onnx_conversion.py \ - -b \ - -r \ - -e \ - -o \ - -j - -Convert ONNX to TensorRT -~~~~~~~~~~~~~~~~~~~~~~~~~ - -For optimized inference, convert the ONNX model to TensorRT. - -.. code-block:: bash - - # : training output directory, : root of the cloned COMPASS repo - cd / - python3 /trt_conversion.py \ - -o \ - -t - -Deployment ----------- - -ROS2 Deployment -~~~~~~~~~~~~~~~ - -The trained COMPASS policy can be deployed using the ROS2 deployment framework. -Refer to the `COMPASS ROS2 Deployment Guide`_ for detailed instructions on deploying the policy in simulation or on real robots. - -The ROS2 deployment supports: - -- Isaac Sim integration for simulation testing -- Zero-shot sim-to-real transfer for real robot deployment -- Object navigation integration with object localization modules - -Sim-to-Real Deployment -~~~~~~~~~~~~~~~~~~~~~~ - -COMPASS policies trained on NuRec Real2Sim environments are designed for zero-shot sim-to-real transfer. -The Real2Sim assets provide a bridge between simulation and reality, enabling policies trained in simulation to work directly on real robots. - -For sim-to-real deployment: - -1. Export the trained policy to ONNX or TensorRT format (see Model Export section) -2. Use the ROS2 deployment framework to run inference on the real robot -3. Integrate with visual SLAM (e.g., cuVSLAM) for robot state estimation -4. The policy will output velocity commands based on camera observations and goal poses - -Troubleshooting ---------------- - -Common Issues -~~~~~~~~~~~~~ - -**Issue: "Failed to sample collision free poses"** - -This error occurs when the collision checking is too strict for the environment. Solutions: -- Reduce ``goal_pose_collision_distance`` and ``start_pose_collision_distance`` in the config -- Enable ``precompute_valid_poses`` to precompute valid pose locations -- Check that the occupancy map files are correctly placed in the ``omap/`` directory - -**Issue: High GPU memory usage** - -- Reduce the number of environments using ``--num_envs`` -- For Real2Sim environments, start with 32-64 environments - -**Issue: Slow pose sampling** - -- Enable ``--precompute_valid_poses`` flag to precompute valid poses -- This is especially important for Real2Sim environments with constrained spaces - -Configuration Tips -~~~~~~~~~~~~~~~~~~ - -For NuRec Real2Sim environments: -- Use collision distances of 0.5m or less for more constrained environments -- Enable precomputed valid poses for constrained environments -- Use environment spacing of 500m to accommodate larger scenes - -.. _Isaac Lab Installation Guide: https://isaac-sim.github.io/IsaacLab/v2.0.0/source/setup/installation/index.html -.. _Isaac Sim Installation Guide: https://docs.isaacsim.omniverse.nvidia.com/latest/installation/install_workstation.html -.. _Isaac Sim pip Installation Guide: https://docs.isaacsim.omniverse.nvidia.com/latest/installation/install_python.html -.. _Hugging Face security tokens documentation: https://huggingface.co/docs/hub/security-tokens -.. _COMPASS Repository: https://github.com/NVlabs/COMPASS -.. _COMPASS ROS2 Deployment Guide: https://github.com/NVlabs/COMPASS/tree/main/ros2_deployment -.. _PhysicalAI-Robotics-NuRec dataset: https://huggingface.co/datasets/nvidia/PhysicalAI-Robotics-NuRec +The guide covers Isaac Sim / Isaac Lab installation, COMPASS setup, downloading and +registering NuRec Real2Sim scenes, training a residual RL specialist, evaluation, +ONNX / TensorRT export, and ROS2 / sim-to-real deployment. From d39c8bd35598c6feecfe4b3be0f740a37afe4468 Mon Sep 17 00:00:00 2001 From: ooctipus Date: Mon, 8 Jun 2026 18:32:38 -0700 Subject: [PATCH 23/40] Fix AutoMate PhysX sizing and assembly ID validation (#6038) ## Summary - increase AutoMate assembly/disassembly PhysX GPU collision stack size from the default 2**26 to 2**27 - reject placeholder/non-5-digit AutoMate assembly IDs in the run helpers before they mutate config or launch simulation - update AutoMate docs to use a concrete runnable assembly ID example - add a lightweight config/helper regression test and an isaaclab_tasks changelog fragment ## Rationale The reported Windows beta2 disassembly run for assembly_id 00032 asks PhysX for a collision stack of roughly 75-86 MB, above the default 2**26 bytes. This keeps the memory change scoped to AutoMate's high-contact 128-env tasks instead of raising the global PhysX default for unrelated environments. A second reported DGX Spark command passed the literal docs placeholder `ASSEMBLY_ID`, which was written into the task config and only failed later as a missing remote USD path. The helpers now fail fast with an argparse message before launching Kit. ## Validation - `python3 tools/changelog/cli.py check develop` - `python3 -m py_compile source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py source/isaaclab_tasks/test/contrib/test_automate_cfg.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py` - `.venv/bin/python -m pytest source/isaaclab_tasks/test/contrib/test_automate_cfg.py` - `uvx ruff==0.14.10 check --fix source/isaaclab_tasks/test/contrib/test_automate_cfg.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py` - `uvx ruff==0.14.10 format source/isaaclab_tasks/test/contrib/test_automate_cfg.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py` - `git diff --check` - `.venv/bin/python source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py --assembly_id=ASSEMBLY_ID --train --max_iterations 10` exits at argparse with the placeholder-specific message and does not mutate the task config Could not run the full PhysX/Kit repro locally because this machine's uv environment does not have Isaac Sim/Kit on PYTHONPATH; the command fails before simulation with Isaac Sim not installed. --- .../changelog.d/fix-automate-collision-stack.rst | 5 +++++ .../isaaclab_tasks/contrib/automate/assembly_env_cfg.py | 1 + .../isaaclab_tasks/contrib/automate/disassembly_env_cfg.py | 1 + .../isaaclab_tasks/contrib/automate/run_disassembly_w_id.py | 3 +++ .../isaaclab_tasks/contrib/automate/run_w_id.py | 3 +++ 5 files changed, 13 insertions(+) create mode 100644 source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst diff --git a/source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst b/source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst new file mode 100644 index 000000000000..f10f973072fe --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Increased the AutoMate assembly and disassembly PhysX GPU collision stack to avoid dropped contacts at the default 128 environments. +* Updated AutoMate run helpers and docs to reject placeholder assembly IDs before launching simulation. diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py index a8dae7034eb3..6e83de596c50 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py @@ -118,6 +118,7 @@ class AssemblyEnvCfg(DirectRLEnvCfg): friction_correlation_distance=0.00625, gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, + gpu_collision_stack_size=2**27, gpu_max_num_partitions=1, # Important for stable simulation. ), physics_material=RigidBodyMaterialCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py index c5c197393b65..2880902455f0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py @@ -119,6 +119,7 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): friction_correlation_distance=0.00625, gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, + gpu_collision_stack_size=2**27, gpu_max_num_partitions=1, # Important for stable simulation. ), physics_material=RigidBodyMaterialCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py index 130a2428ca9a..d585f9ab138c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_disassembly_w_id.py @@ -53,6 +53,9 @@ def main(): parser.add_argument("--seed", type=int, default=-1, help="Random seed.") args = parser.parse_args() + if args.assembly_id == "ASSEMBLY_ID": + parser.error("replace ASSEMBLY_ID with an AutoMate assembly ID, for example 00032") + os.makedirs(args.disassembly_dir, exist_ok=True) update_task_param( diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py index ad9b184fb687..1d09b8f30a43 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py @@ -57,6 +57,9 @@ def main(): parser.add_argument("--max_iterations", type=int, default=1500, help="Number of iteration for policy learning.") args = parser.parse_args() + if args.assembly_id == "ASSEMBLY_ID": + parser.error("replace ASSEMBLY_ID with an AutoMate assembly ID, for example 00032") + update_task_param(args.cfg_path, args.assembly_id, args.train, args.log_eval) # avoid the warning of low GPU occupancy for SoftDTWCUDA function From 49bc6431eec5b4b2b1aaec8eff93be72116afbcb Mon Sep 17 00:00:00 2001 From: ooctipus Date: Mon, 8 Jun 2026 18:57:07 -0700 Subject: [PATCH 24/40] Guard env destructors during Python shutdown (#6031) ## Summary - Skip environment destructor cleanup once Python import shutdown has started (`sys.meta_path is None`). - Apply the guard consistently to `DirectRLEnv`, `DirectMARLEnv`, and `ManagerBasedEnv`. - Add regression coverage that verifies destructors still close during normal runtime but do not call `close()` after import shutdown begins. ## Validation - `PYTHONPATH=/tmp/isaaclab-directrl-del/source/isaaclab /home/zhengyuz/Projects/IsaacLab.wt/decouple-physics-events/env_isaaclab/bin/python -m pytest source/isaaclab/test/envs/test_env_destructors.py -q` - `git diff --check` - `python -m py_compile source/isaaclab/isaaclab/envs/direct_rl_env.py source/isaaclab/isaaclab/envs/direct_marl_env.py source/isaaclab/isaaclab/envs/manager_based_env.py source/isaaclab/test/envs/test_env_destructors.py` - `python3 tools/changelog/cli.py check _tmp-upstream-develop` - Shortened Newton RL-Games repro completed with no `Exception ignored`, `sys.meta_path is None`, `ImportError`, or shutdown traceback: `Isaac-Repose-Cube-Allegro-Direct-v0`, `presets=newton`, `--headless`, `--max_iterations 1`, `--num_envs 2048` --- .../changelog.d/fix-env-del-shutdown.rst | 4 ++ .../isaaclab/isaaclab/envs/direct_marl_env.py | 9 ++- .../isaaclab/isaaclab/envs/direct_rl_env.py | 9 ++- .../isaaclab/envs/manager_based_env.py | 9 ++- .../test/envs/test_env_destructors.py | 58 +++++++++++++++++++ 5 files changed, 80 insertions(+), 9 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-env-del-shutdown.rst create mode 100644 source/isaaclab/test/envs/test_env_destructors.py diff --git a/source/isaaclab/changelog.d/fix-env-del-shutdown.rst b/source/isaaclab/changelog.d/fix-env-del-shutdown.rst new file mode 100644 index 000000000000..ef77e3fea523 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-env-del-shutdown.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Prevented environment destructors from emitting cleanup tracebacks after Python import shutdown begins. diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 7b0f89f4e4df..9ebc983c6da8 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -82,6 +82,9 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar RuntimeError: If a simulation context already exists. The environment must always create one since it configures the simulation context and controls the simulation. """ + # The env remains closed until initialization completes. + self._is_closed = True + # check that the config is valid cfg.validate() # Resolve any preset-wrapper fields (PresetCfg subclasses or old-style ``presets`` dicts) @@ -92,7 +95,6 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar # store the render mode self.render_mode = render_mode # initialize internal variables - self._is_closed = False self._physics_handles_decimation = False # set the seed for the environment @@ -114,6 +116,7 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar except Exception: self.sim.clear_instance() raise + self._is_closed = False def _init_sim(self, render_mode: str | None = None, **kwargs): """Complete environment initialization after the SimulationContext is created. @@ -266,9 +269,9 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # print the environment information print("[INFO]: Completed setting up the environment...") - def __del__(self, _sys_is_finalizing=sys.is_finalizing): + def __del__(self, _sys=sys): """Cleanup for the environment.""" - if not _sys_is_finalizing(): + if not self._is_closed and not _sys.is_finalizing() and _sys.meta_path is not None: self.close() """ diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 82fc2a87809d..bfe97948ac4a 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -87,6 +87,9 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs RuntimeError: If a simulation context already exists. The environment must always create one since it configures the simulation context and controls the simulation. """ + # The env remains closed until initialization completes. + self._is_closed = True + # check that the config is valid cfg.validate() # Resolve any preset-wrapper fields to their default variant so that downstream @@ -97,7 +100,6 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs # store the render mode self.render_mode = render_mode # initialize internal variables - self._is_closed = False self._physics_handles_decimation = False # set the seed for the environment @@ -119,6 +121,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs except Exception: self.sim.clear_instance() raise + self._is_closed = False def _init_sim(self, render_mode: str | None = None, **kwargs): """Complete environment initialization after the SimulationContext is created. @@ -288,9 +291,9 @@ def _init_sim(self, render_mode: str | None = None, **kwargs): # print the environment information print("[INFO]: Completed setting up the environment...") - def __del__(self, _sys_is_finalizing=sys.is_finalizing): + def __del__(self, _sys=sys): """Cleanup for the environment.""" - if not _sys_is_finalizing(): + if not self._is_closed and not _sys.is_finalizing() and _sys.meta_path is not None: self.close() """ diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 5c0d017e10a1..ff081fc48044 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -86,6 +86,9 @@ def __init__(self, cfg: ManagerBasedEnvCfg): RuntimeError: If a simulation context already exists. The environment must always create one since it configures the simulation context and controls the simulation. """ + # The env remains closed until initialization completes. + self._is_closed = True + # check that the config is valid cfg.validate() # Resolve any preset-wrapper fields (PresetCfg subclasses or old-style ``presets`` dicts) @@ -94,7 +97,6 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # store inputs to class self.cfg = cfg # initialize internal variables - self._is_closed = False self._physics_handles_decimation = False # set the seed for the environment @@ -125,6 +127,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): if created_sim: self.sim.clear_instance() raise + self._is_closed = False def _init_sim(self): """Complete environment initialization after the SimulationContext is created. @@ -258,9 +261,9 @@ def _init_sim(self): if self.cfg.num_rerenders_on_reset == 0: self.cfg.num_rerenders_on_reset = 1 - def __del__(self, _sys_is_finalizing=sys.is_finalizing): + def __del__(self, _sys=sys): """Cleanup for the environment.""" - if not _sys_is_finalizing(): + if not self._is_closed and not _sys.is_finalizing() and _sys.meta_path is not None: self.close() """ diff --git a/source/isaaclab/test/envs/test_env_destructors.py b/source/isaaclab/test/envs/test_env_destructors.py new file mode 100644 index 000000000000..92b81a114b3c --- /dev/null +++ b/source/isaaclab/test/envs/test_env_destructors.py @@ -0,0 +1,58 @@ +# 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 + +from __future__ import annotations + +import pytest + +from isaaclab.envs import DirectMARLEnv, DirectRLEnv, ManagerBasedEnv + + +@pytest.mark.parametrize("env_cls", [DirectRLEnv, DirectMARLEnv, ManagerBasedEnv]) +def test_env_destructor_closes_before_shutdown(env_cls, monkeypatch): + """Environment destructors should still close open envs during normal runtime.""" + + closed = False + + def close(_self): + nonlocal closed + closed = True + + env = object.__new__(env_cls) + env._is_closed = False + monkeypatch.setattr(env_cls, "close", close) + + env.__del__() + + assert closed + + +@pytest.mark.parametrize("env_cls", [DirectRLEnv, DirectMARLEnv, ManagerBasedEnv]) +def test_env_destructor_skips_close_when_already_closed(env_cls, monkeypatch): + """Environment destructors should not re-enter close after normal cleanup.""" + + def close(_self): + raise AssertionError("close should not be called for an already closed env") + + env = object.__new__(env_cls) + env._is_closed = True + monkeypatch.setattr(env_cls, "close", close) + + env.__del__() + + +@pytest.mark.parametrize("env_cls", [DirectRLEnv, DirectMARLEnv, ManagerBasedEnv]) +def test_env_destructor_skips_close_after_import_shutdown(env_cls, monkeypatch): + """Environment destructors should not run cleanup after import machinery is torn down.""" + + def close(_self): + raise ImportError("sys.meta_path is None, Python is likely shutting down") + + env = object.__new__(env_cls) + env._is_closed = False + monkeypatch.setattr(env_cls, "close", close) + monkeypatch.setattr("sys.meta_path", None) + + env.__del__() From 4a049643fc40f559fa44214155fc0963dbe25a95 Mon Sep 17 00:00:00 2001 From: Mustafa H <34825877+StafaH@users.noreply.github.com> Date: Mon, 8 Jun 2026 22:31:02 -0400 Subject: [PATCH 25/40] Fix failing SKRL multi-gpu training error (#6035) # Description Fixes a skrl error where jax experimental is not imported and must be imported manually ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../changelog.d/fix-skrl-jax-multihost-import.rst | 6 ++++++ source/isaaclab_rl/isaaclab_rl/skrl.py | 2 ++ 2 files changed, 8 insertions(+) create mode 100644 source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst diff --git a/source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst b/source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst new file mode 100644 index 000000000000..52048ef93974 --- /dev/null +++ b/source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst @@ -0,0 +1,6 @@ +Fixed +^^^^^ + +* Fixed :func:`~isaaclab_rl.skrl.SkrlVecEnvWrapper` failing to import the JAX wrapper on recent JAX + versions by preloading the ``jax.experimental.multihost_utils`` submodule that skrl's distributed + models reference without importing. diff --git a/source/isaaclab_rl/isaaclab_rl/skrl.py b/source/isaaclab_rl/isaaclab_rl/skrl.py index ebd66697fbb1..300d924be7d4 100644 --- a/source/isaaclab_rl/isaaclab_rl/skrl.py +++ b/source/isaaclab_rl/isaaclab_rl/skrl.py @@ -92,6 +92,8 @@ def SkrlVecEnvWrapper( if ml_framework.startswith("torch"): from skrl.envs.wrappers.torch import wrap_env elif ml_framework.startswith("jax"): + # preload submodule that skrl's distributed models use without importing (broken on recent JAX) + import jax.experimental.multihost_utils # noqa: F401 from skrl.envs.wrappers.jax import wrap_env elif ml_framework.startswith("warp"): from skrl.envs.wrappers.warp import wrap_env From 197d6e86d8bae88ffe5d4fcfe4fd7d4926216919 Mon Sep 17 00:00:00 2001 From: Mustafa H <34825877+StafaH@users.noreply.github.com> Date: Mon, 8 Jun 2026 22:47:57 -0400 Subject: [PATCH 26/40] Fix optional loading of kit extensions (#6045) Fix for failure to load the following command: `python -u scripts/reinforcement_learning/skrl/play.py --task Isaac-Velocity-Rough-Anymal-C-Direct-v0 --visualizer kit ` Due to missing extensions ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- apps/isaaclab.python.kit | 4 ++-- .../changelog.d/fix-kit-wheeled-robots-optional.rst | 9 +++++++++ 2 files changed, 11 insertions(+), 2 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst diff --git a/apps/isaaclab.python.kit b/apps/isaaclab.python.kit index 282057c0ab00..d9dbfd942a6c 100644 --- a/apps/isaaclab.python.kit +++ b/apps/isaaclab.python.kit @@ -30,8 +30,8 @@ keywords = ["experience", "app", "usd"] "isaacsim.replicator.behavior" = {} "isaacsim.robot.policy.examples" = {} "isaacsim.robot.schema" = {} -"isaacsim.robot.experimental.wheeled_robots" = {} -"isaacsim.robot.wheeled_robots.nodes" = {} +"isaacsim.robot.experimental.wheeled_robots" = { optional = true } +"isaacsim.robot.wheeled_robots.nodes" = { optional = true } "isaacsim.sensors.experimental.physics" = {} "isaacsim.sensors.experimental.rtx" = {} "isaacsim.simulation_app" = {} diff --git a/source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst b/source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst new file mode 100644 index 000000000000..c80cc2d0d19e --- /dev/null +++ b/source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst @@ -0,0 +1,9 @@ +Fixed +^^^^^ + +* Fixed the ``isaaclab.python.kit`` GUI experience failing to start with a Kit + dependency-solver error on Isaac Sim builds that do not ship + ``isaacsim.robot.experimental.wheeled_robots`` or + ``isaacsim.robot.wheeled_robots.nodes``. These extensions are not imported by + Isaac Lab and are now declared optional, so the experience loads regardless of + the Isaac Sim build. From cc87cc880d23c49dbb10adc6f80cee21c1ff6dcc Mon Sep 17 00:00:00 2001 From: Mustafa H <34825877+StafaH@users.noreply.github.com> Date: Mon, 8 Jun 2026 22:49:06 -0400 Subject: [PATCH 27/40] Refactor and cleanup core lift tasks (#6013) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Consolidates the rigid and soft Franka lifting tasks into a single `isaaclab_tasks.core.lift` package, eliminating the duplicated `lift_franka_soft` task and its parallel `mdp` module. Soft and cloth variants now live as configs alongside the rigid one and share a common MDP package. #### Changes #### Package consolidation (breaking) - Moved `isaaclab_tasks.core.lift_franka_soft` under `isaaclab_tasks.core.lift.config.franka_soft`, next to the rigid `franka` config. - Merged the deformable MDP terms (observations, rewards, terminations) into the shared `isaaclab_tasks.core.lift.mdp` package instead of a separate per-variant `mdp`. The old `lift_franka_soft/mdp` module is removed. #### Environment IDs (breaking) - Dropped the `-v0` version suffix from all lift Gym environment IDs: - `Isaac-Lift-Cube-Franka-v0` → `Isaac-Lift-Cube-Franka` - `Isaac-Lift-Cube-Franka-Play-v0` → `Isaac-Lift-Cube-Franka-Play` - `Isaac-Lift-Soft-Franka-v0` → `Isaac-Lift-Soft-Franka` - `Isaac-Lift-Cloth-Franka-v0` → `Isaac-Lift-Cloth-Franka` #### Fixes - Renamed the `Isaac-Lift-Cloth-Franka` physics preset from the misspelled `newton_mjwarp_vdb` to `newton_mjwarp_vbd`, matching the soft-body task and the underlying VBD solver. - The cloth `RewardsCfg`, which duplicated the soft task's rewards verbatim, now inherits them instead of redefining. #### Misc - Updated imports, docs, benchmarks, and tests to reference the new module paths and environment IDs. - Minor docstring/comment cleanup in `lift_env_cfg.py`. #### Migration ```python # Before from isaaclab_tasks.core.lift_franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg # After from isaaclab_tasks.core.lift.config.franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg # Deformable MDP terms now come from the shared package from isaaclab_tasks.core.lift.mdp import deformable_lifted ``` Update any `gym.make(...)` / `--task` calls to use the unversioned environment IDs listed above. ## Checklist - [ ] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [ ] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [ ] I have made corresponding changes to the documentation - [ ] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [ ] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [ ] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../newton/newton-manager-abstraction.rst | 4 +- .../newton/using-vbd-solver.rst | 12 +- docs/source/overview/environments.rst | 14 +- scripts/benchmarks/benchmark_hydra_resolve.py | 4 +- scripts/benchmarks/benchmark_lazy_export.py | 2 +- .../state_machine/lift_franka_soft.py | 18 +- .../mhaiderbhai-merge-lift-tasks.skip | 1 + .../envs/test_action_state_recorder_term.py | 2 +- .../mhaiderbhai-merge-lift-tasks.skip | 1 + .../test/export/test_rsl_rl_export_flow.py | 4 +- .../mhaiderbhai-merge-lift-tasks.major.rst | 27 +++ .../core/lift/config/franka/__init__.py | 11 +- .../config/franka_soft}/__init__.py | 7 +- .../config/franka_soft}/agents/__init__.py | 0 .../franka_soft}/agents/rsl_rl_ppo_cfg.py | 0 .../franka_soft}/franka_cloth_env_cfg.py | 89 ++-------- .../franka_soft}/franka_soft_env_cfg.py | 59 +++---- .../isaaclab_tasks/core/lift/lift_env_cfg.py | 13 +- .../isaaclab_tasks/core/lift/mdp/__init__.pyi | 35 +++- .../core/lift/mdp/observations.py | 103 ++++++++++- .../isaaclab_tasks/core/lift/mdp/rewards.py | 93 +++++++++- .../core/lift/mdp/terminations.py | 64 ++++++- .../core/lift_franka_soft/mdp/__init__.py | 10 -- .../core/lift_franka_soft/mdp/__init__.pyi | 28 --- .../core/lift_franka_soft/mdp/observations.py | 115 ------------ .../core/lift_franka_soft/mdp/rewards.py | 167 ------------------ .../test/benchmarking/configs.yaml | 4 +- .../test/core/test_environment_determinism.py | 2 +- tools/environ_docs.py | 1 - tools/test_settings.py | 2 +- 30 files changed, 404 insertions(+), 488 deletions(-) create mode 100644 source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip create mode 100644 source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip create mode 100644 source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst rename source/isaaclab_tasks/isaaclab_tasks/core/{lift_franka_soft => lift/config/franka_soft}/__init__.py (86%) rename source/isaaclab_tasks/isaaclab_tasks/core/{lift_franka_soft => lift/config/franka_soft}/agents/__init__.py (100%) rename source/isaaclab_tasks/isaaclab_tasks/core/{lift_franka_soft => lift/config/franka_soft}/agents/rsl_rl_ppo_cfg.py (100%) rename source/isaaclab_tasks/isaaclab_tasks/core/{lift_franka_soft => lift/config/franka_soft}/franka_cloth_env_cfg.py (66%) rename source/isaaclab_tasks/isaaclab_tasks/core/{lift_franka_soft => lift/config/franka_soft}/franka_soft_env_cfg.py (91%) delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.py delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.pyi delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/observations.py delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/rewards.py diff --git a/docs/source/overview/core-concepts/physical-backends/newton/newton-manager-abstraction.rst b/docs/source/overview/core-concepts/physical-backends/newton/newton-manager-abstraction.rst index 312d0c5bb792..39909caa27c3 100644 --- a/docs/source/overview/core-concepts/physical-backends/newton/newton-manager-abstraction.rst +++ b/docs/source/overview/core-concepts/physical-backends/newton/newton-manager-abstraction.rst @@ -176,9 +176,9 @@ You can exercise this coupling path with the Franka soft-body lifting task: .. code-block:: bash - ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Lift-Soft-Franka-v0 --num_envs 1 --visualizer kit + ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Lift-Soft-Franka --num_envs 1 --visualizer kit -For the surface-deformable cloth variant, use ``--task Isaac-Lift-Cloth-Franka-v0``. +For the surface-deformable cloth variant, use ``--task Isaac-Lift-Cloth-Franka``. This environment configures diff --git a/docs/source/overview/core-concepts/physical-backends/newton/using-vbd-solver.rst b/docs/source/overview/core-concepts/physical-backends/newton/using-vbd-solver.rst index 93bc3fcaccdf..e6b30c9ac12f 100644 --- a/docs/source/overview/core-concepts/physical-backends/newton/using-vbd-solver.rst +++ b/docs/source/overview/core-concepts/physical-backends/newton/using-vbd-solver.rst @@ -30,13 +30,13 @@ deformable tasks: .. code-block:: bash - ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Lift-Soft-Franka-v0 --num_envs 1 --visualizer kit + ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Lift-Soft-Franka --num_envs 1 --visualizer kit For the surface-deformable cloth variant, use: .. code-block:: bash - ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Lift-Cloth-Franka-v0 --num_envs 1 --visualizer kit + ./isaaclab.sh -p scripts/environments/zero_agent.py --task Isaac-Lift-Cloth-Franka --num_envs 1 --visualizer kit Both tasks configure MJWarp for the rigid Franka and VBD for the deformable object through @@ -69,11 +69,11 @@ normal Newton fields: The Franka soft-body task defines a ``newton_mjwarp_vbd`` preset that couples MJWarp and VBD: -.. literalinclude:: ../../../../../../source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py +.. literalinclude:: ../../../../../../source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_soft_env_cfg.py :language: python :start-at: class PhysicsCfg :end-at: default = newton_mjwarp_vbd - :emphasize-lines: 4-32 + :emphasize-lines: 3-15 The important pieces are: @@ -91,13 +91,13 @@ You can select the deformable Newton preset globally: .. code-block:: bash - ./isaaclab.sh train --rl_library rsl_rl --task=Isaac-Lift-Soft-Franka-v0 physics=newton_mjwarp_vbd + ./isaaclab.sh train --rl_library rsl_rl --task=Isaac-Lift-Soft-Franka physics=newton_mjwarp_vbd or select the physics field directly: .. code-block:: bash - ./isaaclab.sh train --rl_library rsl_rl --task=Isaac-Lift-Soft-Franka-v0 env.sim.physics=newton_mjwarp_vbd + ./isaaclab.sh train --rl_library rsl_rl --task=Isaac-Lift-Soft-Franka env.sim.physics=newton_mjwarp_vbd Use the direct path override when only one task field should use the VBD preset. Use ``physics=newton_mjwarp_vbd`` when you want every matching preset field in diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index bf6656e0dbed..08ca2372f504 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -303,10 +303,10 @@ for the lift-cube environment: .. |reach-franka-link| replace:: `Isaac-Reach-Franka <../../../source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/joint_pos_env_cfg.py>`__ .. |reach-ur10-link| replace:: `Isaac-Reach-UR10 <../../../source/isaaclab_tasks/isaaclab_tasks/core/reach/config/ur_10/joint_pos_env_cfg.py>`__ .. |deploy-reach-ur10e-link| replace:: `Isaac-Deploy-Reach-UR10e-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/reach/config/ur_10e/joint_pos_env_cfg.py>`__ -.. |lift-cube-link| replace:: `Isaac-Lift-Cube-Franka-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py>`__ +.. |lift-cube-link| replace:: `Isaac-Lift-Cube-Franka <../../../source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py>`__ .. |lift-cube-ik-abs-link| replace:: `Isaac-Lift-Cube-Franka-IK-Abs-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/franka/ik_abs_env_cfg.py>`__ .. |lift-cube-ik-rel-link| replace:: `Isaac-Lift-Cube-Franka-IK-Rel-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/franka/ik_rel_env_cfg.py>`__ -.. |lift-soft-franka-link| replace:: `Isaac-Lift-Soft-Franka-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py>`__ +.. |lift-soft-franka-link| replace:: `Isaac-Lift-Soft-Franka <../../../source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_soft_env_cfg.py>`__ .. |cabi-franka-link| replace:: `Isaac-Open-Drawer-Franka-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/cabinet/config/franka/joint_pos_env_cfg.py>`__ .. |franka-direct-link| replace:: `Isaac-Franka-Cabinet-Direct-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env.py>`__ .. |cube-allegro-link| replace:: `Isaac-Repose-Cube-Allegro-v0 <../../../source/isaaclab_tasks/isaaclab_tasks/core/inhand/config/allegro_hand/allegro_env_cfg.py>`__ @@ -1070,11 +1070,11 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) - **physics=** ``newton_mjwarp``, ``physx`` - * - Isaac-Lift-Cloth-Franka-v0 + * - Isaac-Lift-Cloth-Franka - - Manager Based - **rsl_rl** (PPO) - - **physics=** ``newton_mjwarp_vdb`` + - **physics=** ``newton_mjwarp_vbd`` * - Isaac-Lift-Cube-Franka-IK-Abs-v0 - - Manager Based @@ -1085,8 +1085,8 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - - - * - Isaac-Lift-Cube-Franka-v0 - - Isaac-Lift-Cube-Franka-Play-v0 + * - Isaac-Lift-Cube-Franka + - Isaac-Lift-Cube-Franka-Play - Manager Based - **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) - @@ -1095,7 +1095,7 @@ inferencing, including reading from an already trained checkpoint and disabling - Manager Based - **rl_games** (PPO), **rsl_rl** (PPO) - - * - Isaac-Lift-Soft-Franka-v0 + * - Isaac-Lift-Soft-Franka - - Manager Based - **rsl_rl** (PPO) diff --git a/scripts/benchmarks/benchmark_hydra_resolve.py b/scripts/benchmarks/benchmark_hydra_resolve.py index 3379d7b438c5..c12eb102c8d6 100644 --- a/scripts/benchmarks/benchmark_hydra_resolve.py +++ b/scripts/benchmarks/benchmark_hydra_resolve.py @@ -65,7 +65,7 @@ class Case: Case("cartpole_manager", "Isaac-Cartpole"), Case("cartpole_camera_presets", "Isaac-Cartpole-Camera-Direct", "rl_games_cfg_entry_point"), Case("anymal_rough", "Isaac-Velocity-Rough-Anymal-C-v0"), - Case("franka_lift_cube", "Isaac-Lift-Cube-Franka-v0"), + Case("franka_lift_cube", "Isaac-Lift-Cube-Franka"), Case( "cartpole_camera_newton_ovrtx", "Isaac-Cartpole-Camera-Direct", @@ -83,7 +83,7 @@ class Case: Case("ant_manager", "Isaac-Ant"), Case("humanoid_manager", "Isaac-Humanoid", "rsl_rl_cfg_entry_point"), Case("franka_reach", "Isaac-Reach-Franka"), - Case("franka_lift_cube_agent", "Isaac-Lift-Cube-Franka-v0", "sb3_cfg_entry_point"), + Case("franka_lift_cube_agent", "Isaac-Lift-Cube-Franka", "sb3_cfg_entry_point"), Case("kuka_allegro_lift", "Isaac-Dexsuite-Kuka-Allegro-Lift-v0", "rsl_rl_cfg_entry_point"), Case( "kuka_allegro_lift_single_camera", diff --git a/scripts/benchmarks/benchmark_lazy_export.py b/scripts/benchmarks/benchmark_lazy_export.py index 58a61c27cdec..064e1d68d2a7 100644 --- a/scripts/benchmarks/benchmark_lazy_export.py +++ b/scripts/benchmarks/benchmark_lazy_export.py @@ -50,7 +50,7 @@ "Isaac-Humanoid", "Isaac-Velocity-Flat-Anymal-D-v0", "Isaac-Reach-Franka", - "Isaac-Lift-Cube-Franka-v0", + "Isaac-Lift-Cube-Franka", "Isaac-Dexsuite-Kuka-Allegro-Reorient-v0", "Isaac-Navigation-Flat-Anymal-C-v0", "Isaac-Stack-Cube-Franka-v0", diff --git a/scripts/environments/state_machine/lift_franka_soft.py b/scripts/environments/state_machine/lift_franka_soft.py index ac10e19af15c..2f60832fa8bf 100644 --- a/scripts/environments/state_machine/lift_franka_soft.py +++ b/scripts/environments/state_machine/lift_franka_soft.py @@ -24,7 +24,7 @@ # add argparse arguments parser = argparse.ArgumentParser(description="Pick and lift a deformable with a robotic arm.") parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.") -parser.add_argument("--task", type=str, default="Isaac-Lift-Soft-Franka-v0", help="The task to run.") +parser.add_argument("--task", type=str, default="Isaac-Lift-Soft-Franka", help="The task to run.") parser.add_argument("--video", action="store_true", default=False, help="Record a video of the rollout.") parser.add_argument("--video_length", type=int, default=500, help="Length of the recorded video (in env steps).") parser.add_argument( @@ -63,8 +63,8 @@ from isaaclab.assets.deformable_object.deformable_object_data import DeformableObjectData import isaaclab_tasks # noqa: F401 -from isaaclab_tasks.core.lift_franka_soft.franka_cloth_env_cfg import FrankaClothEnvCfg -from isaaclab_tasks.core.lift_franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg +from isaaclab_tasks.core.lift.config.franka_soft.franka_cloth_env_cfg import FrankaClothEnvCfg +from isaaclab_tasks.core.lift.config.franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg from isaaclab_tasks.utils.parse_cfg import parse_env_cfg # initialize warp @@ -284,24 +284,24 @@ def compute(self, ee_pose: torch.Tensor, object_pose: torch.Tensor, des_object_p def main(): # create environment render_mode = "rgb_array" if args_cli.video else None - if args_cli.task == "Isaac-Lift-Soft-Franka-v0": + if args_cli.task == "Isaac-Lift-Soft-Franka": # parse configuration env_cfg: FrankaSoftEnvCfg = parse_env_cfg( - "Isaac-Lift-Soft-Franka-v0", + "Isaac-Lift-Soft-Franka", device=args_cli.device, num_envs=args_cli.num_envs, ) env_cfg.viewer.eye = (2.1, 1.0, 1.3) - env = gym.make("Isaac-Lift-Soft-Franka-v0", cfg=env_cfg, render_mode=render_mode) - elif args_cli.task == "Isaac-Lift-Soft-Franka-Cloth-v0": + env = gym.make("Isaac-Lift-Soft-Franka", cfg=env_cfg, render_mode=render_mode) + elif args_cli.task == "Isaac-Lift-Cloth-Franka": # parse configuration env_cfg: FrankaClothEnvCfg = parse_env_cfg( - "Isaac-Lift-Cloth-Franka-v0", + "Isaac-Lift-Cloth-Franka", device=args_cli.device, num_envs=args_cli.num_envs, ) env_cfg.viewer.eye = (2.1, 1.0, 1.3) - env = gym.make("Isaac-Lift-Cloth-Franka-v0", cfg=FrankaClothEnvCfg(), render_mode=render_mode) + env = gym.make("Isaac-Lift-Cloth-Franka", cfg=FrankaClothEnvCfg(), render_mode=render_mode) else: raise ValueError(f"Unknown task: {args_cli.task}") diff --git a/source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip b/source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip new file mode 100644 index 000000000000..f91aafa24891 --- /dev/null +++ b/source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip @@ -0,0 +1 @@ +Test-only: updated lift task IDs in tests to match the consolidated/renamed environments. diff --git a/source/isaaclab/test/envs/test_action_state_recorder_term.py b/source/isaaclab/test/envs/test_action_state_recorder_term.py index 9e3a27115aa7..2e269c552120 100644 --- a/source/isaaclab/test/envs/test_action_state_recorder_term.py +++ b/source/isaaclab/test/envs/test_action_state_recorder_term.py @@ -83,7 +83,7 @@ def check_initial_state_recorder_term(env): assert are_states_equal, output_log -@pytest.mark.parametrize("task_name", ["Isaac-Lift-Cube-Franka-v0"]) +@pytest.mark.parametrize("task_name", ["Isaac-Lift-Cube-Franka"]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("num_envs", [1, 2]) def test_action_state_recorder_terms(task_name, device, num_envs, temp_dir): diff --git a/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip b/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip new file mode 100644 index 000000000000..f91aafa24891 --- /dev/null +++ b/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip @@ -0,0 +1 @@ +Test-only: updated lift task IDs in tests to match the consolidated/renamed environments. diff --git a/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py b/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py index 64aa39bccf0f..9ba5e85297c7 100644 --- a/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py +++ b/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py @@ -83,8 +83,8 @@ "Isaac-Reach-UR10", "Isaac-Reach-UR10-Play", # Manipulation Lift - "Isaac-Lift-Cube-Franka-v0", - "Isaac-Lift-Cube-Franka-Play-v0", + "Isaac-Lift-Cube-Franka", + "Isaac-Lift-Cube-Franka-Play", # Manipulation Cabinet "Isaac-Open-Drawer-Franka-v0", "Isaac-Open-Drawer-Franka-Play-v0", diff --git a/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst b/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst new file mode 100644 index 000000000000..b129f035d180 --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst @@ -0,0 +1,27 @@ +Changed +^^^^^^^ + +* **Breaking:** Consolidated the rigid and soft Franka lifting tasks into a single + :mod:`isaaclab_tasks.core.lift` package. The former ``isaaclab_tasks.core.lift_franka_soft`` + package moved under :mod:`isaaclab_tasks.core.lift.config.franka_soft`, alongside the existing + rigid ``franka`` config, to keep the rigid and soft variants separated. Update imports such as + ``from isaaclab_tasks.core.lift_franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg`` to + ``from isaaclab_tasks.core.lift.config.franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg``. + The deformable MDP terms were merged into the shared :mod:`isaaclab_tasks.core.lift.mdp` package + (rather than a separate per-variant ``mdp``); import them from there, e.g. + ``from isaaclab_tasks.core.lift.mdp import deformable_lifted``. +* **Breaking:** Renamed the lift Gym environment IDs to drop the ``-v0`` version suffix. Update + ``gym.make`` / ``--task`` calls: + + * ``Isaac-Lift-Cube-Franka-v0`` → ``Isaac-Lift-Cube-Franka``. + * ``Isaac-Lift-Cube-Franka-Play-v0`` → ``Isaac-Lift-Cube-Franka-Play``. + * ``Isaac-Lift-Soft-Franka-v0`` → ``Isaac-Lift-Soft-Franka``. + * ``Isaac-Lift-Cloth-Franka-v0`` → ``Isaac-Lift-Cloth-Franka``. + +Fixed +^^^^^ + +* Renamed the ``Isaac-Lift-Cloth-Franka`` physics preset from the misspelled ``newton_mjwarp_vdb`` + to ``newton_mjwarp_vbd``, matching the soft-body task and the underlying VBD solver. The cloth + ``RewardsCfg``, which duplicated the soft task's rewards verbatim, is now inherited instead of + redefined. diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/__init__.py index b38193616335..a0e1b23ae498 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/__init__.py @@ -2,9 +2,10 @@ # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause + import gymnasium as gym -from . import agents +from isaaclab_tasks.core.lift.config.franka import agents ## # Register Gym environments. @@ -15,8 +16,9 @@ ## gym.register( - id="Isaac-Lift-Cube-Franka-v0", + id="Isaac-Lift-Cube-Franka", entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, kwargs={ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:FrankaCubeLiftEnvCfg", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg", @@ -24,12 +26,12 @@ "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", }, - disable_env_checker=True, ) gym.register( - id="Isaac-Lift-Cube-Franka-Play-v0", + id="Isaac-Lift-Cube-Franka-Play", entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, kwargs={ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:FrankaCubeLiftEnvCfg_PLAY", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:LiftCubePPORunnerCfg", @@ -37,5 +39,4 @@ "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", }, - disable_env_checker=True, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/__init__.py similarity index 86% rename from source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/__init__.py rename to source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/__init__.py index 0a4c52549e07..e7e8c8e789e9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/__init__.py @@ -5,15 +5,14 @@ import gymnasium as gym -from . import agents +from isaaclab_tasks.core.lift.config.franka_soft import agents ## # Register Gym environments. ## - gym.register( - id="Isaac-Lift-Soft-Franka-v0", + id="Isaac-Lift-Soft-Franka", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ @@ -23,7 +22,7 @@ ) gym.register( - id="Isaac-Lift-Cloth-Franka-v0", + id="Isaac-Lift-Cloth-Franka", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/agents/__init__.py similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/agents/__init__.py rename to source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/agents/__init__.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/agents/rsl_rl_ppo_cfg.py similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/agents/rsl_rl_ppo_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/agents/rsl_rl_ppo_cfg.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_cloth_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_cloth_env_cfg.py similarity index 66% rename from source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_cloth_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_cloth_env_cfg.py index 249b9999b737..f3dafaf9426e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_cloth_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_cloth_env_cfg.py @@ -7,7 +7,6 @@ from __future__ import annotations -from isaaclab_newton.physics import MJWarpSolverCfg from isaaclab_newton.sim.schemas import NewtonDeformableBodyPropertiesCfg from isaaclab_newton.sim.spawners.materials import NewtonSurfaceDeformableBodyMaterialCfg @@ -15,16 +14,20 @@ from isaaclab.assets import AssetBaseCfg from isaaclab.assets.deformable_object import DeformableObjectCfg from isaaclab.managers import EventTermCfg as EventTerm -from isaaclab.managers import RewardTermCfg as RewTerm from isaaclab.managers import SceneEntityCfg from isaaclab.utils.configclass import configclass -from isaaclab_contrib.deformable.newton_manager_cfg import CoupledMJWarpVBDSolverCfg, NewtonModelCfg, VBDSolverCfg +from isaaclab_contrib.deformable.newton_manager_cfg import NewtonModelCfg +from isaaclab_tasks.core.lift import mdp from isaaclab_tasks.utils import PresetCfg -from . import mdp -from .franka_soft_env_cfg import DeformableNewtonCfg, FrankaSoftEnvCfg, _FrankaSoftSceneCfg +from .franka_soft_env_cfg import ( + DeformableNewtonCfg, + FrankaSoftEnvCfg, + _FrankaSoftSceneCfg, + coupled_mjwarp_vbd_solver_cfg, +) from .franka_soft_env_cfg import EventCfg as FrankaSoftEventCfg ## @@ -40,27 +43,10 @@ @configclass class PhysicsCfg(PresetCfg): - # Newton physics: MJWarp rigid + VBD soft, one-way coupled + # Newton physics: MJWarp rigid + VBD soft, two-way coupled # (matches newton/examples/softbody/example_softbody_franka.py) - newton_mjwarp_vdb: DeformableNewtonCfg = DeformableNewtonCfg( - solver_cfg=CoupledMJWarpVBDSolverCfg( - rigid_solver_cfg=MJWarpSolverCfg( - njmax=40, - nconmax=20, - ls_iterations=20, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ccd_iterations=100, - ), - soft_solver_cfg=VBDSolverCfg( - iterations=10, - integrate_with_external_rigid_solver=True, - particle_enable_self_contact=False, - particle_collision_detection_interval=-1, - ), - coupling_mode="two_way", - ), + newton_mjwarp_vbd: DeformableNewtonCfg = DeformableNewtonCfg( + solver_cfg=coupled_mjwarp_vbd_solver_cfg(), model_cfg=NewtonModelCfg( soft_contact_ke=1e3, soft_contact_kd=1e-5, @@ -73,14 +59,14 @@ class PhysicsCfg(PresetCfg): use_cuda_graph=True, ) - default = newton_mjwarp_vdb + default = newton_mjwarp_vbd @configclass class DeformableCfg(PresetCfg): """Preset config for the deformable object, matching the Newton example.""" - newton_mjwarp_vdb: DeformableObjectCfg = DeformableObjectCfg( + newton_mjwarp_vbd: DeformableObjectCfg = DeformableObjectCfg( prim_path="/World/envs/env_.*/Deformable", init_state=DeformableObjectCfg.InitialStateCfg(pos=(0.4, 0.0, 0.2)), spawn=sim_utils.MeshRectangleCfg( @@ -100,7 +86,7 @@ class DeformableCfg(PresetCfg): ), ) - default = newton_mjwarp_vdb + default = newton_mjwarp_vbd @configclass @@ -138,52 +124,6 @@ class ActionsCfg: ) -@configclass -class RewardsCfg: - """Lift-to-target reward for a deformable object.""" - - reaching_deformable = RewTerm( - func=mdp.deformable_ee_distance, - params={"std": 0.1, "asset_cfg": SceneEntityCfg("deformable")}, - weight=5.0, - ) - lifting_deformable = RewTerm( - func=mdp.deformable_lifted, - params={"minimal_height": 0.04, "asset_cfg": SceneEntityCfg("deformable")}, - weight=5.0, - ) - deformable_goal_tracking = RewTerm( - func=mdp.deformable_com_goal_distance, - params={ - "std": 0.3, - "minimal_height": 0.075, - "command_name": "deformable_pose", - "asset_cfg": SceneEntityCfg("deformable"), - }, - weight=16.0, - ) - deformable_goal_tracking_fine_grained = RewTerm( - func=mdp.deformable_com_goal_distance, - params={ - "std": 0.05, - "minimal_height": 0.075, - "command_name": "deformable_pose", - "asset_cfg": SceneEntityCfg("deformable"), - }, - weight=5.0, - ) - - action_rate = RewTerm(func=mdp.action_rate_l2, weight=-1e-2) - gripper_close = RewTerm( - func=mdp.gripper_close_action, - params={"action_name": "gripper_action"}, - weight=-1.0, - ) - joint_vel = RewTerm(func=mdp.joint_vel_l2, weight=-1e-2) - joint_torque = RewTerm(func=mdp.joint_torques_l2, weight=-1e-4) - joint_acc = RewTerm(func=mdp.joint_acc_l2, weight=-1e-4) - - @configclass class EventCfg(FrankaSoftEventCfg): """Reset and startup events for the Franka cloth environment.""" @@ -215,7 +155,6 @@ class FrankaClothEnvCfg(FrankaSoftEnvCfg): # Basic settings actions: ActionsCfg = ActionsCfg() # MDP settings - rewards: RewardsCfg = RewardsCfg() events: EventCfg = EventCfg() def __post_init__(self) -> None: diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_soft_env_cfg.py similarity index 91% rename from source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_soft_env_cfg.py index 26019ee40665..944eae786801 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka_soft/franka_soft_env_cfg.py @@ -3,13 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Configuration for the Franka deformable lifting environment. - -The scene mirrors ``newton/examples/softbody/example_softbody_franka.py``: -a Franka Panda manipulator on a tabletop with a tetrahedral deformable object simulated -by VBD. The RL task is to lift the deformable object's centre of mass to a randomised target -position sampled in the robot's root frame. -""" +"""Configuration for the Franka deformable lifting environment.""" from __future__ import annotations @@ -42,10 +36,9 @@ from isaaclab_contrib.deformable.newton_manager_cfg import CoupledMJWarpVBDSolverCfg, NewtonModelCfg, VBDSolverCfg +from isaaclab_tasks.core.lift import mdp from isaaclab_tasks.utils import PresetCfg -from . import mdp - ## # Pre-defined configs ## @@ -63,6 +56,28 @@ POISSONS_RATIO = 0.25 +def coupled_mjwarp_vbd_solver_cfg() -> CoupledMJWarpVBDSolverCfg: + """MJWarp-rigid + VBD-soft, two-way coupled solver shared by the soft and cloth lift tasks.""" + return CoupledMJWarpVBDSolverCfg( + rigid_solver_cfg=MJWarpSolverCfg( + njmax=40, + nconmax=20, + ls_iterations=20, + cone="pyramidal", + impratio=1, + integrator="implicitfast", + ccd_iterations=100, + ), + soft_solver_cfg=VBDSolverCfg( + iterations=10, + integrate_with_external_rigid_solver=True, + particle_enable_self_contact=False, + particle_collision_detection_interval=-1, + ), + coupling_mode="two_way", + ) + + @configclass class DeformableNewtonCfg(NewtonCfg): """NewtonCfg extended with model-level contact parameters for deformable objects. @@ -118,27 +133,9 @@ class DeformableCfg(PresetCfg): @configclass class PhysicsCfg(PresetCfg): - # Newton physics: MJWarp rigid + VBD soft, one-way coupled - # (matches newton/examples/softbody/example_softbody_franka.py) + # Newton physics: MJWarp rigid + VBD soft, two-way coupled newton_mjwarp_vbd: DeformableNewtonCfg = DeformableNewtonCfg( - solver_cfg=CoupledMJWarpVBDSolverCfg( - rigid_solver_cfg=MJWarpSolverCfg( - njmax=40, - nconmax=20, - ls_iterations=20, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ccd_iterations=100, - ), - soft_solver_cfg=VBDSolverCfg( - iterations=10, - integrate_with_external_rigid_solver=True, - particle_enable_self_contact=False, - particle_collision_detection_interval=-1, - ), - coupling_mode="two_way", - ), + solver_cfg=coupled_mjwarp_vbd_solver_cfg(), model_cfg=NewtonModelCfg( soft_contact_ke=1e4, soft_contact_kd=1e-5, @@ -199,10 +196,6 @@ class _FrankaSoftSceneCfg(InteractiveSceneCfg): ) # lights - # dome_light: AssetBaseCfg = AssetBaseCfg( - # prim_path="/World/light", - # spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=2000.0), - # ) sky_light = AssetBaseCfg( prim_path="/World/skyLight", spawn=sim_utils.DomeLightCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/lift_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/lift_env_cfg.py index f26f7703eb0c..4cc7c27adda7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/lift_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/lift_env_cfg.py @@ -24,7 +24,7 @@ from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass -from . import mdp +from isaaclab_tasks.core.lift import mdp ## # Scene definition @@ -33,10 +33,7 @@ @configclass class ObjectTableSceneCfg(InteractiveSceneCfg): - """Configuration for the lift scene with a robot and a object. - This is the abstract base implementation, the exact scene is defined in the derived classes - which need to set the target object, robot and end-effector frames - """ + """Configuration for the lift scene with a robot and a object.""" # robots: will be populated by agent env cfg robot: ArticulationCfg = MISSING @@ -45,7 +42,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): # target object: will be populated by agent env cfg object: RigidObjectCfg | DeformableObjectCfg = MISSING - # Table + # table table = AssetBaseCfg( prim_path="{ENV_REGEX_NS}/Table", init_state=AssetBaseCfg.InitialStateCfg(pos=[0.5, 0, 0], rot=[0, 0, 0.707, 0.707]), @@ -77,7 +74,7 @@ class CommandsCfg: object_pose = mdp.UniformPoseCommandCfg( asset_name="robot", - body_name=MISSING, # will be set by agent env cfg + body_name=MISSING, # will be set by derived env cfg resampling_time_range=(5.0, 5.0), debug_vis=True, ranges=mdp.UniformPoseCommandCfg.Ranges( @@ -90,7 +87,7 @@ class CommandsCfg: class ActionsCfg: """Action specifications for the MDP.""" - # will be set by agent env cfg + # will be set by derived env cfg arm_action: mdp.JointPositionActionCfg | mdp.DifferentialInverseKinematicsActionCfg = MISSING gripper_action: mdp.BinaryJointPositionActionCfg = MISSING diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/__init__.pyi b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/__init__.pyi index a3487daa9a59..40ff99138e80 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/__init__.pyi +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/__init__.pyi @@ -4,14 +4,43 @@ # SPDX-License-Identifier: BSD-3-Clause __all__ = [ + # observations "object_position_in_robot_root_frame", + "deformable_com_in_robot_root_frame", + "DeformableSampledPointsInRobotRootFrame", + # rewards "object_ee_distance", "object_goal_distance", "object_is_lifted", + "deformable_lifted", + "deformable_ee_distance", + "deformable_com_goal_distance", + "gripper_close_action", + # terminations "object_reached_goal", + "deformable_com_below_minimum", + "deformable_outside_table_bounds", + "ee_below_minimum", ] -from .observations import object_position_in_robot_root_frame -from .rewards import object_ee_distance, object_goal_distance, object_is_lifted -from .terminations import object_reached_goal +from .observations import ( + DeformableSampledPointsInRobotRootFrame, + deformable_com_in_robot_root_frame, + object_position_in_robot_root_frame, +) +from .rewards import ( + deformable_com_goal_distance, + deformable_ee_distance, + deformable_lifted, + gripper_close_action, + object_ee_distance, + object_goal_distance, + object_is_lifted, +) +from .terminations import ( + deformable_com_below_minimum, + deformable_outside_table_bounds, + ee_below_minimum, + object_reached_goal, +) from isaaclab.envs.mdp import * diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/observations.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/observations.py index 06659683d770..84d01fac2c7d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/observations.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/observations.py @@ -3,18 +3,23 @@ # # SPDX-License-Identifier: BSD-3-Clause +"""Observation functions for the rigid and deformable lift tasks.""" + from __future__ import annotations +from collections.abc import Sequence from typing import TYPE_CHECKING import torch +import warp as wp -from isaaclab.managers import SceneEntityCfg +from isaaclab.managers import ManagerTermBase, SceneEntityCfg from isaaclab.utils.math import subtract_frame_transforms if TYPE_CHECKING: - from isaaclab.assets import RigidObject + from isaaclab.assets import Articulation, DeformableObject, RigidObject from isaaclab.envs import ManagerBasedRLEnv + from isaaclab.managers import ObservationTermCfg def object_position_in_robot_root_frame( @@ -28,3 +33,97 @@ def object_position_in_robot_root_frame( object_pos_w = object.data.root_pos_w.torch[:, :3] object_pos_b, _ = subtract_frame_transforms(robot.data.root_pos_w.torch, robot.data.root_quat_w.torch, object_pos_w) return object_pos_b + + +def deformable_com_in_robot_root_frame( + env: ManagerBasedRLEnv, + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), + robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"), +) -> torch.Tensor: + """Position of the deformable object's COM in the robot's root frame [m]. + + The COM is the mean of the deformable's nodal positions (see + :attr:`~isaaclab.assets.DeformableObject.data.root_pos_w`). + + Returns: + Tensor of shape ``(num_envs, 3)``. + """ + asset: DeformableObject = env.scene[asset_cfg.name] + robot: Articulation = env.scene[robot_cfg.name] + com_w = wp.to_torch(asset.data.root_pos_w) + com_b, _ = subtract_frame_transforms(wp.to_torch(robot.data.root_pos_w), wp.to_torch(robot.data.root_quat_w), com_w) + return com_b + + +class DeformableSampledPointsInRobotRootFrame(ManagerTermBase): + """Sampled deformable nodal points expressed in the robot's root frame. + + The point indices are sampled on reset, then reused within the episode so + each observed point follows the same material node over time. + """ + + def __init__(self, cfg: ObservationTermCfg, env: ManagerBasedRLEnv): + super().__init__(cfg, env) + + self.asset_cfg: SceneEntityCfg = cfg.params.get("asset_cfg", SceneEntityCfg("deformable")) + self.robot_cfg: SceneEntityCfg = cfg.params.get("robot_cfg", SceneEntityCfg("robot")) + self.num_points: int = cfg.params.get("num_points", 20) + + asset: DeformableObject = env.scene[self.asset_cfg.name] + self.num_nodes = asset.data.nodal_pos_w.shape[1] + self.node_ids = torch.empty(env.num_envs, self.num_points, dtype=torch.long, device=env.device) + self.reset() + + def reset(self, env_ids: Sequence[int] | None = None) -> None: + """Resample observed deformable nodes for the selected environments.""" + if env_ids is None: + env_ids = slice(None) + num_envs = self.num_envs + else: + num_envs = len(env_ids) + + if self.num_points <= self.num_nodes: + self.node_ids[env_ids] = ( + torch.rand((num_envs, self.num_nodes), device=self.device).topk(self.num_points, dim=1).indices + ) + else: + self.node_ids[env_ids] = torch.randint(self.num_nodes, (num_envs, self.num_points), device=self.device) + + def __call__( + self, + env: ManagerBasedRLEnv, + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), + robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"), + num_points: int = 20, + ) -> torch.Tensor: + """Sample deformable nodal positions in the robot's root frame. + + Args: + env: The environment instance. + asset_cfg: The deformable object entity. + robot_cfg: The robot entity providing the reference frame. + num_points: Number of sampled points. + + Returns: + Flattened tensor of shape ``(num_envs, 3 * num_points)`` with sampled + point positions [m] in the robot root frame. + """ + asset: DeformableObject = env.scene[asset_cfg.name] + robot: Articulation = env.scene[robot_cfg.name] + if num_points != self.num_points: + raise ValueError( + f"Requested {num_points} deformable points, but this term was initialized with {self.num_points}." + ) + + nodal_pos_w = asset.data.nodal_pos_w.torch + sampled_points_w = nodal_pos_w.gather(1, self.node_ids.unsqueeze(-1).expand(-1, -1, 3)) + + flat_sampled_points_w = sampled_points_w.reshape(-1, 3) + root_pos_w = robot.data.root_pos_w.torch.unsqueeze(1).expand(-1, num_points, -1) + root_quat_w = robot.data.root_quat_w.torch.unsqueeze(1).expand(-1, num_points, -1) + sampled_points_b, _ = subtract_frame_transforms( + root_pos_w.reshape(-1, 3), + root_quat_w.reshape(-1, 4), + flat_sampled_points_w, + ) + return sampled_points_b.view(env.num_envs, -1) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/rewards.py index 77517708c053..bbee850bcb43 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/rewards.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/rewards.py @@ -3,17 +3,20 @@ # # SPDX-License-Identifier: BSD-3-Clause +"""Reward functions for the rigid and deformable lift tasks.""" + from __future__ import annotations from typing import TYPE_CHECKING import torch +import warp as wp from isaaclab.managers import ManagerTermBase, RewardTermCfg, SceneEntityCfg from isaaclab.utils.math import combine_frame_transforms if TYPE_CHECKING: - from isaaclab.assets import RigidObject + from isaaclab.assets import Articulation, DeformableObject, RigidObject from isaaclab.envs import ManagerBasedRLEnv from isaaclab.sensors import FrameTransformer @@ -90,3 +93,91 @@ def __call__( if success_threshold is not None: self._succeeded |= is_lifted & (distance < success_threshold) return is_lifted.float() * (1 - torch.tanh(distance / std)) + + +def deformable_lifted( + env: ManagerBasedRLEnv, + minimal_height: float, + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), +) -> torch.Tensor: + """Reward if the deformable COM is above a minimum height. + + Args: + env: The environment instance. + minimal_height: Minimum COM height [m]. + asset_cfg: The deformable object entity. + + Returns: + Reward tensor with shape ``(num_envs,)``. + """ + asset: DeformableObject = env.scene[asset_cfg.name] + com_z = wp.to_torch(asset.data.root_pos_w)[:, 2] + return torch.where(com_z > minimal_height, 1.0, 0.0) + + +def deformable_ee_distance( + env: ManagerBasedRLEnv, + std: float, + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), + ee_frame_cfg: SceneEntityCfg = SceneEntityCfg("ee_frame"), +) -> torch.Tensor: + """Reward reaching the deformable's nearest nodal point with the end-effector. + + Args: + env: The environment instance. + std: The tanh kernel standard deviation [m]. + asset_cfg: The deformable object entity. + ee_frame_cfg: The end-effector frame entity. + + Returns: + Reward tensor with shape ``(num_envs,)``. + """ + asset: DeformableObject = env.scene[asset_cfg.name] + ee_frame: FrameTransformer = env.scene[ee_frame_cfg.name] + nodal_pos_w = wp.to_torch(asset.data.nodal_pos_w) + ee_w = wp.to_torch(ee_frame.data.target_pos_w)[..., 0, :] + distance = torch.linalg.norm(nodal_pos_w - ee_w.unsqueeze(1), dim=2).min(dim=1).values + return 1.0 - torch.tanh(distance / std) + + +def deformable_com_goal_distance( + env: ManagerBasedRLEnv, + std: float, + minimal_height: float, + command_name: str, + robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"), + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), +) -> torch.Tensor: + """Reward tracking of the goal position by the deformable's COM (tanh kernel). + + Only credits when the COM is above ``minimal_height`` (i.e. the object is lifted). + The command is interpreted as ``[x, y, z, qw, qx, qy, qz]`` in the robot's root frame. + """ + robot: Articulation = env.scene[robot_cfg.name] + asset: DeformableObject = env.scene[asset_cfg.name] + command = env.command_manager.get_command(command_name) + des_pos_b = command[:, :3] + des_pos_w, _ = combine_frame_transforms( + wp.to_torch(robot.data.root_pos_w), wp.to_torch(robot.data.root_quat_w), des_pos_b + ) + com_w = wp.to_torch(asset.data.root_pos_w) + distance = torch.linalg.norm(des_pos_w - com_w, dim=1) + return (com_w[:, 2] > minimal_height) * (1.0 - torch.tanh(distance / std)) + + +def gripper_close_action(env: ManagerBasedRLEnv, action_name: str = "gripper_action") -> torch.Tensor: + """Penalty signal for commanding the gripper to close. + + The binary gripper action uses negative float actions for close commands and + non-negative actions for open commands. + + Args: + env: The environment instance. + action_name: Name of the gripper action term. + + Returns: + Tensor with shape ``(num_envs,)`` containing ``1`` when the gripper is + commanded closed and ``0`` otherwise. + """ + gripper_action = env.action_manager.get_term(action_name).raw_actions + return torch.any(gripper_action < 0.0, dim=1).float() diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/terminations.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/terminations.py index 5342ab669758..0a82fc85bdeb 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/terminations.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/mdp/terminations.py @@ -3,7 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Common functions that can be used to activate certain terminations for the lift task. +"""Termination functions for the rigid and deformable lift tasks. The functions can be passed to the :class:`isaaclab.managers.TerminationTermCfg` object to enable the termination introduced by the function. @@ -14,13 +14,15 @@ from typing import TYPE_CHECKING import torch +import warp as wp from isaaclab.managers import SceneEntityCfg from isaaclab.utils.math import combine_frame_transforms if TYPE_CHECKING: - from isaaclab.assets import RigidObject + from isaaclab.assets import DeformableObject, RigidObject from isaaclab.envs import ManagerBasedRLEnv + from isaaclab.sensors import FrameTransformer def object_reached_goal( @@ -56,3 +58,61 @@ def object_reached_goal( # rewarded if the object is lifted above the threshold return distance < threshold + + +def deformable_com_below_minimum( + env: ManagerBasedRLEnv, + minimum_height: float, + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), +) -> torch.Tensor: + """Termination signal when the deformable's COM falls below ``minimum_height`` [m].""" + asset: DeformableObject = env.scene[asset_cfg.name] + com_z = wp.to_torch(asset.data.root_pos_w)[:, 2] + return com_z < minimum_height + + +def deformable_outside_table_bounds( + env: ManagerBasedRLEnv, + x_bounds: tuple[float, float], + y_bounds: tuple[float, float], + asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), +) -> torch.Tensor: + """Terminate if any deformable nodal point leaves the table footprint. + + Args: + env: The environment instance. + x_bounds: Allowed x-position range in the environment frame [m]. + y_bounds: Allowed y-position range in the environment frame [m]. + asset_cfg: The deformable object entity. + + Returns: + Boolean tensor with shape ``(num_envs,)``. + """ + asset: DeformableObject = env.scene[asset_cfg.name] + nodal_pos = wp.to_torch(asset.data.nodal_pos_w) - env.scene.env_origins.unsqueeze(1) + outside_x = (nodal_pos[..., 0] < x_bounds[0]) | (nodal_pos[..., 0] > x_bounds[1]) + outside_y = (nodal_pos[..., 1] < y_bounds[0]) | (nodal_pos[..., 1] > y_bounds[1]) + return torch.any(outside_x | outside_y, dim=1) + + +def ee_below_minimum( + env: ManagerBasedRLEnv, + minimum_height: float, + ee_frame_cfg: SceneEntityCfg = SceneEntityCfg("ee_frame"), +) -> torch.Tensor: + """Termination signal when the end-effector falls below ``minimum_height`` [m]. + + Height is measured in the environment frame (``z`` of the EE position with the env + origin subtracted), so the threshold is independent of the environment's xy offset. + + Args: + env: The environment instance. + minimum_height: Minimum allowed EE height in the environment frame [m]. + ee_frame_cfg: The end-effector frame entity. + + Returns: + Boolean tensor with shape ``(num_envs,)``. + """ + ee_frame: FrameTransformer = env.scene[ee_frame_cfg.name] + ee_z = wp.to_torch(ee_frame.data.target_pos_w)[..., 0, 2] - env.scene.env_origins[:, 2] + return ee_z < minimum_height diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.py deleted file mode 100644 index 8596e8efb4e7..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.py +++ /dev/null @@ -1,10 +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 - -"""This sub-module contains the functions that are specific to the environment.""" - -from isaaclab.utils.module import lazy_export - -lazy_export() diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.pyi b/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.pyi deleted file mode 100644 index bb8b3af19852..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/__init__.pyi +++ /dev/null @@ -1,28 +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 - -__all__ = [ - "deformable_com_below_minimum", - "deformable_ee_distance", - "deformable_com_goal_distance", - "deformable_com_in_robot_root_frame", - "DeformableSampledPointsInRobotRootFrame", - "deformable_lifted", - "deformable_outside_table_bounds", - "ee_below_minimum", - "gripper_close_action", -] - -from .observations import DeformableSampledPointsInRobotRootFrame, deformable_com_in_robot_root_frame -from .rewards import ( - deformable_com_below_minimum, - deformable_ee_distance, - deformable_com_goal_distance, - deformable_lifted, - deformable_outside_table_bounds, - ee_below_minimum, - gripper_close_action, -) -from isaaclab.envs.mdp import * diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/observations.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/observations.py deleted file mode 100644 index a1aa2fa0aa64..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/observations.py +++ /dev/null @@ -1,115 +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 - -"""Observation functions for the Franka deformable lifting environment.""" - -from __future__ import annotations - -from collections.abc import Sequence -from typing import TYPE_CHECKING - -import torch -import warp as wp - -from isaaclab.managers import ManagerTermBase, SceneEntityCfg -from isaaclab.utils.math import subtract_frame_transforms - -if TYPE_CHECKING: - from isaaclab.assets import Articulation, DeformableObject - from isaaclab.envs import ManagerBasedRLEnv - - -def deformable_com_in_robot_root_frame( - env: ManagerBasedRLEnv, - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), - robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"), -) -> torch.Tensor: - """Position of the deformable object's COM in the robot's root frame [m]. - - The COM is the mean of the deformable's nodal positions (see - :attr:`~isaaclab.assets.DeformableObject.data.root_pos_w`). - - Returns: - Tensor of shape ``(num_envs, 3)``. - """ - asset: DeformableObject = env.scene[asset_cfg.name] - robot: Articulation = env.scene[robot_cfg.name] - com_w = wp.to_torch(asset.data.root_pos_w) - com_b, _ = subtract_frame_transforms(wp.to_torch(robot.data.root_pos_w), wp.to_torch(robot.data.root_quat_w), com_w) - return com_b - - -class DeformableSampledPointsInRobotRootFrame(ManagerTermBase): - """Sampled deformable nodal points expressed in the robot's root frame. - - The point indices are sampled on reset, then reused within the episode so - each observed point follows the same material node over time. - """ - - def __init__(self, cfg, env: ManagerBasedRLEnv): - super().__init__(cfg, env) - - self.asset_cfg: SceneEntityCfg = cfg.params.get("asset_cfg", SceneEntityCfg("deformable")) - self.robot_cfg: SceneEntityCfg = cfg.params.get("robot_cfg", SceneEntityCfg("robot")) - self.num_points: int = cfg.params.get("num_points", 20) - - asset: DeformableObject = env.scene[self.asset_cfg.name] - self.num_nodes = asset.data.nodal_pos_w.shape[1] - self.node_ids = torch.empty(env.num_envs, self.num_points, dtype=torch.long, device=env.device) - self.reset() - - def reset(self, env_ids: Sequence[int] | None = None) -> None: - """Resample observed deformable nodes for the selected environments.""" - if env_ids is None: - env_ids = slice(None) - num_envs = self.num_envs - else: - num_envs = len(env_ids) - - if self.num_points <= self.num_nodes: - self.node_ids[env_ids] = ( - torch.rand((num_envs, self.num_nodes), device=self.device).topk(self.num_points, dim=1).indices - ) - else: - self.node_ids[env_ids] = torch.randint(self.num_nodes, (num_envs, self.num_points), device=self.device) - - def __call__( - self, - env: ManagerBasedRLEnv, - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), - robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"), - num_points: int = 20, - ) -> torch.Tensor: - """Sample deformable nodal positions in the robot's root frame. - - Args: - env: The environment instance. - asset_cfg: The deformable object entity. - robot_cfg: The robot entity providing the reference frame. - num_points: Number of sampled points. - - Returns: - Flattened tensor of shape ``(num_envs, 3 * num_points)`` with sampled - point positions [m] in the robot root frame. - """ - asset: DeformableObject = env.scene[asset_cfg.name] - robot: Articulation = env.scene[robot_cfg.name] - if num_points != self.num_points: - raise ValueError( - f"Requested {num_points} deformable points, but this term was initialized with {self.num_points}." - ) - - nodal_pos_w = asset.data.nodal_pos_w.torch - sampled_points_w = nodal_pos_w.gather(1, self.node_ids.unsqueeze(-1).expand(-1, -1, 3)) - - flat_sampled_points_w = sampled_points_w.reshape(-1, 3) - root_pos_w = robot.data.root_pos_w.torch.unsqueeze(1).expand(-1, num_points, -1) - root_quat_w = robot.data.root_quat_w.torch.unsqueeze(1).expand(-1, num_points, -1) - sampled_points_b, _ = subtract_frame_transforms( - root_pos_w.reshape(-1, 3), - root_quat_w.reshape(-1, 4), - flat_sampled_points_w, - ) - return sampled_points_b.view(env.num_envs, -1) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/rewards.py deleted file mode 100644 index 9811051cd370..000000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/mdp/rewards.py +++ /dev/null @@ -1,167 +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 - -"""Reward and termination functions for the Franka deformable lifting environment.""" - -from __future__ import annotations - -from typing import TYPE_CHECKING - -import torch -import warp as wp - -from isaaclab.managers import SceneEntityCfg -from isaaclab.utils.math import combine_frame_transforms - -if TYPE_CHECKING: - from isaaclab.assets import Articulation, DeformableObject - from isaaclab.envs import ManagerBasedRLEnv - from isaaclab.sensors import FrameTransformer - - -def deformable_lifted( - env: ManagerBasedRLEnv, - minimal_height: float, - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), -) -> torch.Tensor: - """Reward if the deformable COM is above a minimum height. - - Args: - env: The environment instance. - minimal_height: Minimum COM height [m]. - asset_cfg: The deformable object entity. - - Returns: - Reward tensor with shape ``(num_envs,)``. - """ - asset: DeformableObject = env.scene[asset_cfg.name] - com_z = wp.to_torch(asset.data.root_pos_w)[:, 2] - return torch.where(com_z > minimal_height, 1.0, 0.0) - - -def deformable_ee_distance( - env: ManagerBasedRLEnv, - std: float, - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), - ee_frame_cfg: SceneEntityCfg = SceneEntityCfg("ee_frame"), -) -> torch.Tensor: - """Reward reaching the deformable's nearest nodal point with the end-effector. - - Args: - env: The environment instance. - std: The tanh kernel standard deviation [m]. - asset_cfg: The deformable object entity. - ee_frame_cfg: The end-effector frame entity. - - Returns: - Reward tensor with shape ``(num_envs,)``. - """ - asset: DeformableObject = env.scene[asset_cfg.name] - ee_frame: FrameTransformer = env.scene[ee_frame_cfg.name] - nodal_pos_w = wp.to_torch(asset.data.nodal_pos_w) - ee_w = wp.to_torch(ee_frame.data.target_pos_w)[..., 0, :] - distance = torch.linalg.norm(nodal_pos_w - ee_w.unsqueeze(1), dim=2).min(dim=1).values - return 1.0 - torch.tanh(distance / std) - - -def deformable_com_goal_distance( - env: ManagerBasedRLEnv, - std: float, - minimal_height: float, - command_name: str, - robot_cfg: SceneEntityCfg = SceneEntityCfg("robot"), - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), -) -> torch.Tensor: - """Reward tracking of the goal position by the deformable's COM (tanh kernel). - - Only credits when the COM is above ``minimal_height`` (i.e. the object is lifted). - The command is interpreted as ``[x, y, z, qw, qx, qy, qz]`` in the robot's root frame. - """ - robot: Articulation = env.scene[robot_cfg.name] - asset: DeformableObject = env.scene[asset_cfg.name] - command = env.command_manager.get_command(command_name) - des_pos_b = command[:, :3] - des_pos_w, _ = combine_frame_transforms( - wp.to_torch(robot.data.root_pos_w), wp.to_torch(robot.data.root_quat_w), des_pos_b - ) - com_w = wp.to_torch(asset.data.root_pos_w) - distance = torch.linalg.norm(des_pos_w - com_w, dim=1) - return (com_w[:, 2] > minimal_height) * (1.0 - torch.tanh(distance / std)) - - -def gripper_close_action(env: ManagerBasedRLEnv, action_name: str = "gripper_action") -> torch.Tensor: - """Penalty signal for commanding the gripper to close. - - The binary gripper action uses negative float actions for close commands and - non-negative actions for open commands. - - Args: - env: The environment instance. - action_name: Name of the gripper action term. - - Returns: - Tensor with shape ``(num_envs,)`` containing ``1`` when the gripper is - commanded closed and ``0`` otherwise. - """ - gripper_action = env.action_manager.get_term(action_name).raw_actions - return torch.any(gripper_action < 0.0, dim=1).float() - - -def deformable_com_below_minimum( - env: ManagerBasedRLEnv, - minimum_height: float, - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), -) -> torch.Tensor: - """Termination signal when the deformable's COM falls below ``minimum_height`` [m].""" - asset: DeformableObject = env.scene[asset_cfg.name] - com_z = wp.to_torch(asset.data.root_pos_w)[:, 2] - return com_z < minimum_height - - -def deformable_outside_table_bounds( - env: ManagerBasedRLEnv, - x_bounds: tuple[float, float], - y_bounds: tuple[float, float], - asset_cfg: SceneEntityCfg = SceneEntityCfg("deformable"), -) -> torch.Tensor: - """Terminate if any deformable nodal point leaves the table footprint. - - Args: - env: The environment instance. - x_bounds: Allowed x-position range in the environment frame [m]. - y_bounds: Allowed y-position range in the environment frame [m]. - asset_cfg: The deformable object entity. - - Returns: - Boolean tensor with shape ``(num_envs,)``. - """ - asset: DeformableObject = env.scene[asset_cfg.name] - nodal_pos = wp.to_torch(asset.data.nodal_pos_w) - env.scene.env_origins.unsqueeze(1) - outside_x = (nodal_pos[..., 0] < x_bounds[0]) | (nodal_pos[..., 0] > x_bounds[1]) - outside_y = (nodal_pos[..., 1] < y_bounds[0]) | (nodal_pos[..., 1] > y_bounds[1]) - return torch.any(outside_x | outside_y, dim=1) - - -def ee_below_minimum( - env: ManagerBasedRLEnv, - minimum_height: float, - ee_frame_cfg: SceneEntityCfg = SceneEntityCfg("ee_frame"), -) -> torch.Tensor: - """Termination signal when the end-effector falls below ``minimum_height`` [m]. - - Height is measured in the environment frame (``z`` of the EE position with the env - origin subtracted), so the threshold is independent of the environment's xy offset. - - Args: - env: The environment instance. - minimum_height: Minimum allowed EE height in the environment frame [m]. - ee_frame_cfg: The end-effector frame entity. - - Returns: - Boolean tensor with shape ``(num_envs,)``. - """ - ee_frame: FrameTransformer = env.scene[ee_frame_cfg.name] - ee_z = wp.to_torch(ee_frame.data.target_pos_w)[..., 0, 2] - env.scene.env_origins[:, 2] - return ee_z < minimum_height diff --git a/source/isaaclab_tasks/test/benchmarking/configs.yaml b/source/isaaclab_tasks/test/benchmarking/configs.yaml index 0622fc29e617..7551edf967ee 100644 --- a/source/isaaclab_tasks/test/benchmarking/configs.yaml +++ b/source/isaaclab_tasks/test/benchmarking/configs.yaml @@ -61,7 +61,7 @@ fast: episode_length: 875 upper_thresholds: duration: 1800 - sb3:Isaac-Lift-Cube-Franka-v0: + sb3:Isaac-Lift-Cube-Franka: max_iterations: 150 lower_thresholds: reward: 1.5 @@ -159,7 +159,7 @@ full: episode_length: 400 upper_thresholds: duration: 1000 - Isaac-Lift-Cube-Franka-v0: + Isaac-Lift-Cube-Franka: max_iterations: 300 lower_thresholds: reward: 90 diff --git a/source/isaaclab_tasks/test/core/test_environment_determinism.py b/source/isaaclab_tasks/test/core/test_environment_determinism.py index 3ff16a5871bf..91569c509ba7 100644 --- a/source/isaaclab_tasks/test/core/test_environment_determinism.py +++ b/source/isaaclab_tasks/test/core/test_environment_determinism.py @@ -37,7 +37,7 @@ def setup_environment(): "task_name", [ "Isaac-Open-Drawer-Franka-v0", - "Isaac-Lift-Cube-Franka-v0", + "Isaac-Lift-Cube-Franka", ], ) @pytest.mark.parametrize("device", ["cuda", "cpu"]) diff --git a/tools/environ_docs.py b/tools/environ_docs.py index bdf1cff7ea61..0873b8f511d2 100644 --- a/tools/environ_docs.py +++ b/tools/environ_docs.py @@ -35,7 +35,6 @@ "newton_kamino", "newton_mjwarp", "newton_mjwarp_vbd", - "newton_mjwarp_vdb", "ovphysx", "physx", *PresetTarget.all_legacy_aliases().keys(), diff --git a/tools/test_settings.py b/tools/test_settings.py index b24e8a201e66..25ac6a864ea4 100644 --- a/tools/test_settings.py +++ b/tools/test_settings.py @@ -141,7 +141,7 @@ "Isaac-Ant", "Isaac-Cartpole", # manipulation - "Isaac-Lift-Cube-Franka-v0", + "Isaac-Lift-Cube-Franka", "Isaac-Open-Drawer-Franka-v0", # dexterous manipulation "Isaac-Repose-Cube-Allegro-v0", From 0879bd867ac7ba744bc052f361fdda1a2dd3034c Mon Sep 17 00:00:00 2001 From: HuiDong Chen Date: Tue, 9 Jun 2026 11:11:52 +0800 Subject: [PATCH 28/40] Fixed incorrect camera pose in :class:`~isaaclab_newton.sim.views.NewtonSiteFrameView` (#6047) # Description Fixed incorrect camera pose in :class:`~isaaclab_newton.sim.views.NewtonSiteFrameView`. The code change is cherry-picked from #5979 . ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [ ] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../changelog.d/huidongc-fix-incorrect-camera-pose.rst | 4 ++++ .../sim/views/newton_site_frame_view.py | 10 ++++++++-- 2 files changed, 12 insertions(+), 2 deletions(-) create mode 100644 source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst diff --git a/source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst b/source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst new file mode 100644 index 000000000000..9fc4300916b8 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst @@ -0,0 +1,4 @@ +Fixed +^^^^^ + +* Fixed incorrect camera pose in :class:`~isaaclab_newton.sim.views.NewtonSiteFrameView`. diff --git a/source/isaaclab_newton/isaaclab_newton/sim/views/newton_site_frame_view.py b/source/isaaclab_newton/isaaclab_newton/sim/views/newton_site_frame_view.py index a814df64d1fa..8b9b65b7e69a 100644 --- a/source/isaaclab_newton/isaaclab_newton/sim/views/newton_site_frame_view.py +++ b/source/isaaclab_newton/isaaclab_newton/sim/views/newton_site_frame_view.py @@ -14,7 +14,7 @@ from pxr import UsdPhysics import isaaclab.sim as sim_utils -from isaaclab.cloner.cloner_utils import iter_clone_plan_matches +from isaaclab.cloner.cloner_utils import get_suffix, iter_clone_plan_matches from isaaclab.physics import PhysicsEvent from isaaclab.sim.views.base_frame_view import BaseFrameView from isaaclab.utils.string import resolve_matching_names @@ -321,7 +321,13 @@ def _resolve_source_prim( return body_patterns, wp.transform(pos, quat), False, env_ids body_prim = body_prim.GetParent() - ref_prim = stage.GetPrimAtPath(source_root) if source_root is not None else None + ref_path = source_root + if source_root is not None and destination_template is not None: + instance_template = destination_template.partition("{}")[0] + "{}" + source_suffix = get_suffix(source_root, instance_template) + if source_suffix is not None: + ref_path = source_root[: -len(source_suffix)] if source_suffix else source_root + ref_prim = stage.GetPrimAtPath(ref_path) if ref_path is not None else None pos, quat = sim_utils.resolve_prim_pose(prim, ref_prim if ref_prim and ref_prim.IsValid() else None) return None, wp.transform(pos, quat), source_root is not None, env_ids From dc513413f9f2d7f8a4911561b21be7160c73c5fc Mon Sep 17 00:00:00 2001 From: ooctipus Date: Mon, 8 Jun 2026 20:12:14 -0700 Subject: [PATCH 29/40] Remove AutoMate Numba SoftDTW dependency (#6040) ## Summary - Remove `numba` from `isaaclab_tasks` dependencies. - Replace AutoMate's Numba CUDA/CPU-JIT SoftDTW helper with a Torch implementation that runs on the input tensor device. - Add a no-grad anti-diagonal SoftDTW path plus `forward_with_lengths(...)` so the AutoMate reward evaluates padded variable-length reference segments in one batched call instead of one SoftDTW call per environment. - Clean up the autograd SoftDTW path to use a Torch DP table instead of Python row lists, with a clearer docstring. - Remove the Numba CUDA warning environment variable from `run_w_id.py`. - Add focused SoftDTW tests for the no-Numba path, hard DTW, normalized SoftDTW, variable-length padded SoftDTW, and finite backward gradients. ## Rationale The original failure is not a sustainable place to solve with a NumPy pin. AutoMate only needs SoftDTW values for reward computation; it does not require the copied differentiable Numba implementation as a package-level dependency. Keeping Numba also exposes a second failure mode on RTX 5090: the old Numba CUDA kernel can fail at compile time with `CUDA_ERROR_UNSUPPORTED_PTX_VERSION` / unsupported PTX version. This removes the dependency instead of constraining global NumPy resolution. ## Verification - Focused tests pass in the develop venv: `python -m pytest source/isaaclab_tasks/test/contrib/test_automate_soft_dtw.py -q` (`5 passed`). - Focused tests pass in the beta2 venv where Numba import is broken (`5 passed`). - `git diff --check` passes. - `py_compile` passes for the touched Python files. - Old-vs-new SoftDTW CPU forward parity: 594 finite cases across `gamma={0.01,0.1,1.0}`, normalized/non-normalized valid cases, bandwidth `{None,2,20}`, and sequence lengths up to `B=8,N=10,M=100`; max absolute difference was `1.526e-04`. - Mustafa's row/column Torch DP variant matched the current no-grad implementation exactly in direct forward checks; for `B=128,N=10,M=100`, it measured `82.497 ms` on CUDA versus `14.038 ms` for the anti-diagonal no-grad SoftDTW path, so this PR keeps the anti-diagonal path for reward inference while using the cleaner Torch DP-table style for autograd. - For `gamma=0`, the old implementation returns `nan` on a simple hard-DTW case; the new implementation returns the expected hard-DTW value `1.0`. - New SoftDTW autograd smoke test produces finite gradients. - AutoMate reward parity: optimized length-aware reward path matches the original per-env reward loop on synthetic AutoMate-shaped data (`128` envs, `10` robot waypoints, `ref_len=100`, `gamma=0.01`); max absolute error was `0.0` on CPU and CUDA. ## Performance Synthetic AutoMate-shaped reward benchmark on RTX 5090 with Torch `2.10.0+cu128`, `128` envs, `10` robot waypoints, `ref_len=100`, `gamma=0.01`, `no_grad`: | Path | CPU median | CUDA median | CUDA peak allocated delta | | --- | ---: | ---: | ---: | | Per-env Torch reward loop | `141.617 ms` | `355.131 ms` | `15.372 MB` | | Batched length-aware Torch reward | `13.483 ms` | `25.824 ms` | `15.372 MB` | The peak CUDA allocation in this reward benchmark is dominated by the closest-state `torch.cdist` calculation, not by the SoftDTW table. The previous Numba CUDA path could not be timed on this RTX 5090 because it fails locally with `CUDA_ERROR_UNSUPPORTED_PTX_VERSION`; the performance comparison above is against the direct per-env Torch replacement path that this PR would otherwise have used. --- .../fix-automate-numba-constraints.rst | 5 + .../contrib/automate/automate_algo_utils.py | 41 +- .../contrib/automate/run_w_id.py | 7 +- .../contrib/automate/soft_dtw_cuda.py | 477 +++++------------- source/isaaclab_tasks/pyproject.toml | 1 - .../test/contrib/test_automate_soft_dtw.py | 82 +++ 6 files changed, 236 insertions(+), 377 deletions(-) create mode 100644 source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst create mode 100644 source/isaaclab_tasks/test/contrib/test_automate_soft_dtw.py diff --git a/source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst b/source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst new file mode 100644 index 000000000000..85dff4de4ee2 --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Removed AutoMate's Numba dependency by replacing the SoftDTW helper with a + Torch implementation. diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/automate_algo_utils.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/automate_algo_utils.py index 5aa584e9b65b..7c053044f28b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/automate_algo_utils.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/automate_algo_utils.py @@ -88,23 +88,50 @@ def get_imitation_reward_from_dtw(ref_traj, curr_ee_pos, prev_ee_traj, criterion prev_ee_pos = prev_ee_traj[:, 0, :] # select the first ee pos in robot traj min_dist_traj_idx, min_dist_step_idx, min_dist_per_env = get_closest_state_idx(ref_traj, prev_ee_pos) + eef_traj = torch.cat((prev_ee_traj[:, 1:, :], curr_ee_pos.unsqueeze(1)), dim=1) + selected_trajs: list[torch.Tensor] = [] + selected_traj_lengths = torch.empty((curr_ee_pos.shape[0],), dtype=torch.long, device=device) + max_selected_traj_len = 0 + for i in range(curr_ee_pos.shape[0]): - traj_idx = min_dist_traj_idx[i] - step_idx = min_dist_step_idx[i] + traj_idx = int(min_dist_traj_idx[i].item()) + step_idx = int(min_dist_step_idx[i].item()) curr_ee_pos_i = curr_ee_pos[i].reshape(1, 3) # NOTE: in reference trajectories, larger index -> closer to goal traj = ref_traj[traj_idx, step_idx:, :].reshape((1, -1, 3)) _, curr_step_idx, _ = get_closest_state_idx(traj, curr_ee_pos_i) + curr_step_idx = int(curr_step_idx.item()) if curr_step_idx == 0: - selected_pos = ref_traj[traj_idx, step_idx, :].reshape((1, 1, 3)) - selected_traj = torch.cat([selected_pos, selected_pos], dim=1) + selected_traj = ref_traj[traj_idx, step_idx, :].reshape((1, 3)).repeat(2, 1) else: - selected_traj = ref_traj[traj_idx, step_idx : (curr_step_idx + step_idx), :].reshape((1, -1, 3)) - eef_traj = torch.cat((prev_ee_traj[i, 1:, :], curr_ee_pos_i)).reshape((1, -1, 3)) - soft_dtw[i] = criterion(eef_traj, selected_traj) + selected_traj = ref_traj[traj_idx, step_idx : (curr_step_idx + step_idx), :] + + traj_len = selected_traj.shape[0] + selected_trajs.append(selected_traj) + selected_traj_lengths[i] = traj_len + max_selected_traj_len = max(max_selected_traj_len, traj_len) + + if hasattr(criterion, "forward_with_lengths") and not getattr(criterion, "normalize", False): + padded_selected_trajs = torch.zeros( + (curr_ee_pos.shape[0], max_selected_traj_len, ref_traj.shape[-1]), dtype=ref_traj.dtype, device=device + ) + for i, selected_traj in enumerate(selected_trajs): + padded_selected_trajs[i, : selected_traj.shape[0], :] = selected_traj + soft_dtw = criterion.forward_with_lengths(eef_traj, padded_selected_trajs, selected_traj_lengths) + else: + selected_trajs_by_len: dict[int, list[torch.Tensor]] = {} + env_ids_by_len: dict[int, list[int]] = {} + for i, selected_traj in enumerate(selected_trajs): + traj_len = selected_traj.shape[0] + selected_trajs_by_len.setdefault(traj_len, []).append(selected_traj) + env_ids_by_len.setdefault(traj_len, []).append(i) + + for traj_len, selected_trajs_by_curr_len in selected_trajs_by_len.items(): + env_ids = torch.tensor(env_ids_by_len[traj_len], dtype=torch.long, device=device) + soft_dtw[env_ids] = criterion(eef_traj[env_ids], torch.stack(selected_trajs_by_curr_len, dim=0)) w_task_progress = 1 - (min_dist_step_idx / ref_traj.shape[1]) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py index 1d09b8f30a43..da92f7cebe3d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/run_w_id.py @@ -4,7 +4,6 @@ # SPDX-License-Identifier: BSD-3-Clause import argparse -import os import re import subprocess import sys @@ -62,10 +61,6 @@ def main(): update_task_param(args.cfg_path, args.assembly_id, args.train, args.log_eval) - # avoid the warning of low GPU occupancy for SoftDTWCUDA function - env = os.environ.copy() - env["NUMBA_CUDA_LOW_OCCUPANCY_WARNINGS"] = "0" - # build the command if sys.platform.startswith("win"): command = ["isaaclab.bat"] @@ -94,7 +89,7 @@ def main(): command.append(f"--checkpoint={args.checkpoint}") # Run the command - subprocess.run(command, env=env, check=True) + subprocess.run(command, check=True) if __name__ == "__main__": diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/soft_dtw_cuda.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/soft_dtw_cuda.py index 9c0f7a3d4b03..341b9fc9db6d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/soft_dtw_cuda.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/soft_dtw_cuda.py @@ -26,427 +26,178 @@ # SOFTWARE. # ---------------------------------------------------------------------------------------------------------------------- -import math - -import numba.cuda as cuda -import numpy as np import torch -import torch.cuda -from numba import jit, prange -from torch.autograd import Function -# ---------------------------------------------------------------------------------------------------------------------- -@cuda.jit -def compute_softdtw_cuda(D, gamma, bandwidth, max_i, max_j, n_passes, R): - """ - :param seq_len: The length of the sequence (both inputs are assumed to be of the same size) - :param n_passes: 2 * seq_len - 1 (The number of anti-diagonals) - """ - # Each block processes one pair of examples - b = cuda.blockIdx.x - # We have as many threads as seq_len, because the most number of threads we need - # is equal to the number of elements on the largest anti-diagonal - tid = cuda.threadIdx.x - - inv_gamma = 1.0 / gamma - - # Go over each anti-diagonal. Only process threads that fall on the current on the anti-diagonal - for p in range(n_passes): - # The index is actually 'p - tid' but need to force it in-bounds - J = max(0, min(p - tid, max_j - 1)) - - # For simplicity, we define i, j which start from 1 (offset from I, J) - i = tid + 1 - j = J + 1 - - # Only compute if element[i, j] is on the current anti-diagonal, and also is within bounds - if tid + J == p and (tid < max_i and max_j > J): - # Don't compute if outside bandwidth - if not (abs(i - j) > bandwidth > 0): - r0 = -R[b, i - 1, j - 1] * inv_gamma - r1 = -R[b, i - 1, j] * inv_gamma - r2 = -R[b, i, j - 1] * inv_gamma - rmax = max(max(r0, r1), r2) - rsum = math.exp(r0 - rmax) + math.exp(r1 - rmax) + math.exp(r2 - rmax) - softmin = -gamma * (math.log(rsum) + rmax) - R[b, i, j] = D[b, i - 1, j - 1] + softmin - - # Wait for other threads in this block - cuda.syncthreads() +def _soft_dtw_autograd(D: torch.Tensor, gamma: float, bandwidth: float) -> torch.Tensor: + """Compute SoftDTW using Torch ops that preserve autograd.""" + batch_size, len_x, len_y = D.shape + R = torch.full((batch_size, len_x + 2, len_y + 2), float("inf"), device=D.device, dtype=D.dtype) + R[:, 0, 0] = 0 + band_size = int(bandwidth) if bandwidth > 0 else max(len_x, len_y) + for i in range(1, len_x + 1): + j_start = max(1, i - band_size) + j_end = min(len_y, i + band_size) + 1 -# ---------------------------------------------------------------------------------------------------------------------- -@cuda.jit -def compute_softdtw_backward_cuda(D, R, inv_gamma, bandwidth, max_i, max_j, n_passes, E): - k = cuda.blockIdx.x - tid = cuda.threadIdx.x + for j in range(j_start, j_end): + r0 = R[:, i - 1, j - 1] + r1 = R[:, i - 1, j] + r2 = R[:, i, j - 1] - # Indexing logic is the same as above, however, the anti-diagonal needs to - # progress backwards + if gamma == 0: + softmin = torch.minimum(torch.minimum(r0, r1), r2) + else: + previous_costs = torch.stack((r0, r1, r2)) + softmin = -gamma * torch.logsumexp(-previous_costs / gamma, dim=0) - for p in range(n_passes): - # Reverse the order to make the loop go backward - rev_p = n_passes - p - 1 + R[:, i, j] = D[:, i - 1, j - 1] + softmin - # convert tid to I, J, then i, j - J = max(0, min(rev_p - tid, max_j - 1)) + return R[:, len_x, len_y] - i = tid + 1 - j = J + 1 - # Only compute if element[i, j] is on the current anti-diagonal, and also is within bounds - if tid + J == rev_p and (tid < max_i and max_j > J): - if math.isinf(R[k, i, j]): - R[k, i, j] = -math.inf +def _soft_dtw_no_grad(D: torch.Tensor, gamma: float, bandwidth: float) -> torch.Tensor: + """Compute SoftDTW by evaluating each dynamic-programming anti-diagonal in one batched op.""" + batch_size, len_x, len_y = D.shape + R = torch.full((batch_size, len_x + 2, len_y + 2), float("inf"), device=D.device, dtype=D.dtype) + R[:, 0, 0] = 0 - # Don't compute if outside bandwidth - if not (abs(i - j) > bandwidth > 0): - a = math.exp((R[k, i + 1, j] - R[k, i, j] - D[k, i + 1, j]) * inv_gamma) - b = math.exp((R[k, i, j + 1] - R[k, i, j] - D[k, i, j + 1]) * inv_gamma) - c = math.exp((R[k, i + 1, j + 1] - R[k, i, j] - D[k, i + 1, j + 1]) * inv_gamma) - E[k, i, j] = E[k, i + 1, j] * a + E[k, i, j + 1] * b + E[k, i + 1, j + 1] * c + for diag in range(2, len_x + len_y + 1): + i = torch.arange(max(1, diag - len_y), min(len_x, diag - 1) + 1, device=D.device) + j = diag - i - # Wait for other threads in this block - cuda.syncthreads() + if bandwidth > 0: + keep = torch.abs(i - j) <= bandwidth + i = i[keep] + j = j[keep] + if i.numel() == 0: + continue + if gamma == 0: + softmin = torch.minimum(torch.minimum(R[:, i - 1, j - 1], R[:, i - 1, j]), R[:, i, j - 1]) + else: + previous_costs = torch.stack((R[:, i - 1, j - 1], R[:, i - 1, j], R[:, i, j - 1])) + softmin = -gamma * torch.logsumexp(-previous_costs / gamma, dim=0) -# ---------------------------------------------------------------------------------------------------------------------- -class _SoftDTWCUDA(Function): - """ - CUDA implementation is inspired by the diagonal one proposed in https://ieeexplore.ieee.org/document/8400444: - "Developing a pattern discovery method in time series data and its GPU acceleration" - """ + R[:, i, j] = D[:, i - 1, j - 1] + softmin - @staticmethod - def forward(ctx, D, device, gamma, bandwidth): - dev = D.device - dtype = D.dtype - gamma = torch.tensor([gamma], dtype=torch.float, device=device) - bandwidth = torch.tensor([bandwidth], dtype=torch.float, device=device) - - B = D.shape[0] - N = D.shape[1] - M = D.shape[2] - threads_per_block = max(N, M) - n_passes = 2 * threads_per_block - 1 - - # Prepare the output array - R = torch.ones((B, N + 2, M + 2), device=dev, dtype=dtype) * math.inf - R[:, 0, 0] = 0 - - # Run the CUDA kernel. - # Set CUDA's grid size to be equal to the batch size (every CUDA block processes one sample pair) - # Set the CUDA block size to be equal to the length of the longer sequence - # (equal to the size of the largest diagonal) - compute_softdtw_cuda[B, threads_per_block]( - cuda.as_cuda_array(D.detach()), gamma.item(), bandwidth.item(), N, M, n_passes, cuda.as_cuda_array(R) - ) - ctx.save_for_backward(D, R.clone(), gamma, bandwidth) - return R[:, -2, -2] + return R[:, len_x, len_y] - @staticmethod - def backward(ctx, grad_output): - dev = grad_output.device - dtype = grad_output.dtype - D, R, gamma, bandwidth = ctx.saved_tensors - - B = D.shape[0] - N = D.shape[1] - M = D.shape[2] - threads_per_block = max(N, M) - n_passes = 2 * threads_per_block - 1 - - D_ = torch.zeros((B, N + 2, M + 2), dtype=dtype, device=dev) - D_[:, 1 : N + 1, 1 : M + 1] = D - - R[:, :, -1] = -math.inf - R[:, -1, :] = -math.inf - R[:, -1, -1] = R[:, -2, -2] - - E = torch.zeros((B, N + 2, M + 2), dtype=dtype, device=dev) - E[:, -1, -1] = 1 - - # Grid and block sizes are set same as done above for the forward() call - compute_softdtw_backward_cuda[B, threads_per_block]( - cuda.as_cuda_array(D_), - cuda.as_cuda_array(R), - 1.0 / gamma.item(), - bandwidth.item(), - N, - M, - n_passes, - cuda.as_cuda_array(E), - ) - E = E[:, 1 : N + 1, 1 : M + 1] - return grad_output.view(-1, 1, 1).expand_as(E) * E, None, None +def _soft_dtw_variable_y_no_grad( + D: torch.Tensor, y_lengths: torch.Tensor, gamma: float, bandwidth: float +) -> torch.Tensor: + """Compute SoftDTW for a batch where each Y sequence can have a different length.""" + batch_size, len_x, len_y = D.shape + y_lengths = y_lengths.to(device=D.device, dtype=torch.long) + if y_lengths.min().item() < 1 or y_lengths.max().item() > len_y: + raise ValueError("y_lengths entries must be in [1, len_y]") -# ---------------------------------------------------------------------------------------------------------------------- -# -# The following is the CPU implementation based on https://github.com/Sleepwalking/pytorch-softdtw -# Credit goes to Kanru Hua. -# I've added support for batching and pruning. -# -# ---------------------------------------------------------------------------------------------------------------------- -@jit(nopython=True, parallel=True) -def compute_softdtw(D, gamma, bandwidth): - B = D.shape[0] - N = D.shape[1] - M = D.shape[2] - R = np.ones((B, N + 2, M + 2)) * np.inf + R = torch.full((batch_size, len_x + 2, len_y + 2), float("inf"), device=D.device, dtype=D.dtype) R[:, 0, 0] = 0 - for b in prange(B): - for j in range(1, M + 1): - for i in range(1, N + 1): - # Check the pruning condition - if 0 < bandwidth < np.abs(i - j): - continue - - r0 = -R[b, i - 1, j - 1] / gamma - r1 = -R[b, i - 1, j] / gamma - r2 = -R[b, i, j - 1] / gamma - rmax = max(max(r0, r1), r2) - rsum = np.exp(r0 - rmax) + np.exp(r1 - rmax) + np.exp(r2 - rmax) - softmin = -gamma * (np.log(rsum) + rmax) - R[b, i, j] = D[b, i - 1, j - 1] + softmin - return R + for diag in range(2, len_x + len_y + 1): + i = torch.arange(max(1, diag - len_y), min(len_x, diag - 1) + 1, device=D.device) + j = diag - i -# ---------------------------------------------------------------------------------------------------------------------- -@jit(nopython=True, parallel=True) -def compute_softdtw_backward(D_, R, gamma, bandwidth): - B = D_.shape[0] - N = D_.shape[1] - M = D_.shape[2] - D = np.zeros((B, N + 2, M + 2)) - E = np.zeros((B, N + 2, M + 2)) - D[:, 1 : N + 1, 1 : M + 1] = D_ - E[:, -1, -1] = 1 - R[:, :, -1] = -np.inf - R[:, -1, :] = -np.inf - R[:, -1, -1] = R[:, -2, -2] - for k in prange(B): - for j in range(M, 0, -1): - for i in range(N, 0, -1): - if np.isinf(R[k, i, j]): - R[k, i, j] = -np.inf - - # Check the pruning condition - if 0 < bandwidth < np.abs(i - j): - continue - - a0 = (R[k, i + 1, j] - R[k, i, j] - D[k, i + 1, j]) / gamma - b0 = (R[k, i, j + 1] - R[k, i, j] - D[k, i, j + 1]) / gamma - c0 = (R[k, i + 1, j + 1] - R[k, i, j] - D[k, i + 1, j + 1]) / gamma - a = np.exp(a0) - b = np.exp(b0) - c = np.exp(c0) - E[k, i, j] = E[k, i + 1, j] * a + E[k, i, j + 1] * b + E[k, i + 1, j + 1] * c - return E[:, 1 : N + 1, 1 : M + 1] + if bandwidth > 0: + keep = torch.abs(i - j) <= bandwidth + i = i[keep] + j = j[keep] + if i.numel() == 0: + continue + if gamma == 0: + softmin = torch.minimum(torch.minimum(R[:, i - 1, j - 1], R[:, i - 1, j]), R[:, i, j - 1]) + else: + previous_costs = torch.stack((R[:, i - 1, j - 1], R[:, i - 1, j], R[:, i, j - 1])) + softmin = -gamma * torch.logsumexp(-previous_costs / gamma, dim=0) -# ---------------------------------------------------------------------------------------------------------------------- -class _SoftDTW(Function): - """ - CPU implementation based on https://github.com/Sleepwalking/pytorch-softdtw - """ + values = D[:, i - 1, j - 1] + softmin + valid_y = j.unsqueeze(0) <= y_lengths.unsqueeze(1) + R[:, i, j] = torch.where(valid_y, values, torch.full_like(values, float("inf"))) - @staticmethod - def forward(ctx, D, device, gamma, bandwidth): - dev = D.device - dtype = D.dtype - gamma = torch.Tensor([gamma]).to(dev).type(dtype) # dtype fixed - bandwidth = torch.Tensor([bandwidth]).to(dev).type(dtype) - D_ = D.detach().cpu().numpy() - g_ = gamma.item() - b_ = bandwidth.item() - R = torch.Tensor(compute_softdtw(D_, g_, b_)).to(dev).type(dtype) - ctx.save_for_backward(D, R, gamma, bandwidth) - return R[:, -2, -2] + batch_ids = torch.arange(batch_size, device=D.device) + return R[batch_ids, len_x, y_lengths] - @staticmethod - def backward(ctx, grad_output): - dev = grad_output.device - dtype = grad_output.dtype - D, R, gamma, bandwidth = ctx.saved_tensors - D_ = D.detach().cpu().numpy() - R_ = R.detach().cpu().numpy() - g_ = gamma.item() - b_ = bandwidth.item() - E = torch.Tensor(compute_softdtw_backward(D_, R_, g_, b_)).to(dev).type(dtype) - return grad_output.view(-1, 1, 1).expand_as(E) * E, None, None +def _soft_dtw(D: torch.Tensor, gamma: float, bandwidth: float) -> torch.Tensor: + """Compute batched SoftDTW from a pairwise distance tensor. -# ---------------------------------------------------------------------------------------------------------------------- -class SoftDTW(torch.nn.Module): + Args: + D: Pairwise distance tensor of shape ``(batch, len_x, len_y)``. + gamma: SoftDTW smoothing parameter. Set to 0 to compute hard DTW. + bandwidth: Optional Sakoe-Chiba bandwidth. Values <= 0 disable the band constraint. """ - The soft DTW implementation that optionally supports CUDA + if torch.is_grad_enabled() and D.requires_grad: + return _soft_dtw_autograd(D, gamma, bandwidth) + return _soft_dtw_no_grad(D, gamma, bandwidth) + + +class SoftDTW(torch.nn.Module): + """Soft Dynamic Time Warping implemented with Torch tensor operations. + + The ``use_cuda`` and ``device`` arguments are kept for compatibility with the + previous AutoMate SoftDTW helper. The implementation runs on the device of the + input tensors and does not require Numba. """ def __init__(self, use_cuda, device, gamma=1.0, normalize=False, bandwidth=None, dist_func=None): - """Initializes a new instance using the supplied parameters + """Initializes a new instance using the supplied parameters. Args: - - use_cuda: Whether to use the CUDA implementation. - device: The device to run the SoftDTW computation. - gamma: The SoftDTW's gamma parameter. Default is 1.0. + use_cuda: Preserved for API compatibility. Inputs already determine the execution device. + device: Preserved for API compatibility. Inputs already determine the execution device. + gamma: The SoftDTW gamma parameter. Set to 0 for original DTW without smoothing. normalize: Whether to perform normalization. Default is False. - (as discussed in https://github.com/mblondel/soft-dtw/issues/10#issuecomment-383564790) bandwidth: Sakoe-Chiba bandwidth for pruning. Default is None, which disables pruning. - If provided, must be a float. - dist_func: The point-wise distance function to use. Default is None, which - uses a default Euclidean distance function. + dist_func: The point-wise distance function to use. Default is squared Euclidean distance. """ super().__init__() self.normalize = normalize - self.gamma = gamma + self.gamma = float(gamma) self.bandwidth = 0 if bandwidth is None else float(bandwidth) self.use_cuda = use_cuda self.device = device - # Set the distance function if dist_func is not None: self.dist_func = dist_func else: self.dist_func = SoftDTW._euclidean_dist_func - def _get_func_dtw(self, x, y): - """ - Checks the inputs and selects the proper implementation to use. - """ - bx, lx, dx = x.shape - by, ly, dy = y.shape - # Make sure the dimensions match - assert bx == by # Equal batch sizes - assert dx == dy # Equal feature dimensions - - use_cuda = self.use_cuda - - if use_cuda and (lx > 1024 or ly > 1024): # We should be able to spawn enough threads in CUDA - print( - "SoftDTW: Cannot use CUDA because the sequence length > 1024 (the maximum block size supported by CUDA)" - ) - use_cuda = False - - # Finally, return the correct function - return _SoftDTWCUDA.apply if use_cuda else _SoftDTW.apply - @staticmethod def _euclidean_dist_func(x, y): - """ - Calculates the Euclidean distance between each element in x and y per timestep - """ - n = x.size(1) - m = y.size(1) - d = x.size(2) - x = x.unsqueeze(2).expand(-1, n, m, d) - y = y.unsqueeze(1).expand(-1, n, m, d) + """Calculates the squared Euclidean distance between each element in x and y per timestep.""" + num_x = x.size(1) + num_y = y.size(1) + dims = x.size(2) + x = x.unsqueeze(2).expand(-1, num_x, num_y, dims) + y = y.unsqueeze(1).expand(-1, num_x, num_y, dims) return torch.pow(x - y, 2).sum(3) def forward(self, X, Y): - """ - Compute the soft-DTW value between X and Y - :param X: One batch of examples, batch_size x seq_len x dims - :param Y: The other batch of examples, batch_size x seq_len x dims - :return: The computed results - """ - - # Check the inputs and get the correct implementation - func_dtw = self._get_func_dtw(X, Y) - + """Compute the SoftDTW value between ``X`` and ``Y``.""" if self.normalize: - # Stack everything up and run x = torch.cat([X, X, Y]) y = torch.cat([Y, X, Y]) D = self.dist_func(x, y) - out = func_dtw(D, self.device, self.gamma, self.bandwidth) + out = _soft_dtw(D, self.gamma, self.bandwidth) out_xy, out_xx, out_yy = torch.split(out, X.shape[0]) - return out_xy - 1 / 2 * (out_xx + out_yy) - else: - D_xy = self.dist_func(X, Y) - return func_dtw(D_xy, self.device, self.gamma, self.bandwidth) + return out_xy - 0.5 * (out_xx + out_yy) + D_xy = self.dist_func(X, Y) + return _soft_dtw(D_xy, self.gamma, self.bandwidth) -# ---------------------------------------------------------------------------------------------------------------------- -def timed_run(a, b, sdtw): - """ - Runs a and b through sdtw, and times the forward and backward passes. - Assumes that a requires gradients. - :return: timing, forward result, backward result - """ - - from timeit import default_timer as timer - - # Forward pass - start = timer() - forward = sdtw(a, b) - end = timer() - t = end - start - - grad_outputs = torch.ones_like(forward) - - # Backward - start = timer() - grads = torch.autograd.grad(forward, a, grad_outputs=grad_outputs)[0] - end = timer() - - # Total time - t += end - start - - return t, forward, grads - - -# ---------------------------------------------------------------------------------------------------------------------- -def profile(batch_size, seq_len_a, seq_len_b, dims, tol_backward): - sdtw = SoftDTW(False, gamma=1.0, normalize=False) - sdtw_cuda = SoftDTW(True, gamma=1.0, normalize=False) - n_iters = 6 - - print( - f"Profiling forward() + backward() times for batch_size={batch_size}, seq_len_a={seq_len_a}," - f" seq_len_b={seq_len_b}, dims={dims}..." - ) - - times_cpu = [] - times_gpu = [] - - for i in range(n_iters): - a_cpu = torch.rand((batch_size, seq_len_a, dims), requires_grad=True) - b_cpu = torch.rand((batch_size, seq_len_b, dims)) - a_gpu = a_cpu.cuda() - b_gpu = b_cpu.cuda() - - # GPU - t_gpu, forward_gpu, backward_gpu = timed_run(a_gpu, b_gpu, sdtw_cuda) - - # CPU - t_cpu, forward_cpu, backward_cpu = timed_run(a_cpu, b_cpu, sdtw) - - # Verify the results - assert torch.allclose(forward_cpu, forward_gpu.cpu()) - assert torch.allclose(backward_cpu, backward_gpu.cpu(), atol=tol_backward) - - # Ignore the first time we run, in case this is a cold start - # (because timings are off at a cold start of the script) - if i > 0: - times_cpu += [t_cpu] - times_gpu += [t_gpu] - - # Average and log - avg_cpu = np.mean(times_cpu) - avg_gpu = np.mean(times_gpu) - print(" CPU: ", avg_cpu) - print(" GPU: ", avg_gpu) - print(" Speedup: ", avg_cpu / avg_gpu) - print() - + def forward_with_lengths(self, X, Y, y_lengths): + """Compute SoftDTW when each Y sequence is padded to a per-sample length.""" + if self.normalize: + raise ValueError("forward_with_lengths does not support normalize=True") -# ---------------------------------------------------------------------------------------------------------------------- -if __name__ == "__main__": - torch.manual_seed(1234) + if torch.is_grad_enabled() and (X.requires_grad or Y.requires_grad): + outputs = [] + for batch_id, y_length in enumerate(y_lengths.tolist()): + outputs.append(self.forward(X[batch_id : batch_id + 1], Y[batch_id : batch_id + 1, : int(y_length)])) + return torch.cat(outputs) - profile(128, 17, 15, 2, tol_backward=1e-6) - profile(512, 64, 64, 2, tol_backward=1e-4) - profile(512, 256, 256, 2, tol_backward=1e-3) + D_xy = self.dist_func(X, Y) + return _soft_dtw_variable_y_no_grad(D_xy, y_lengths, self.gamma, self.bandwidth) diff --git a/source/isaaclab_tasks/pyproject.toml b/source/isaaclab_tasks/pyproject.toml index c65fa38e3819..613310dacb62 100644 --- a/source/isaaclab_tasks/pyproject.toml +++ b/source/isaaclab_tasks/pyproject.toml @@ -22,7 +22,6 @@ dependencies = [ "torchvision>=0.25.0", "protobuf>=4.25.8,!=5.26.0", "tensorboard", - "numba>=0.63.1", ] [project.urls] diff --git a/source/isaaclab_tasks/test/contrib/test_automate_soft_dtw.py b/source/isaaclab_tasks/test/contrib/test_automate_soft_dtw.py new file mode 100644 index 000000000000..bd330e24a357 --- /dev/null +++ b/source/isaaclab_tasks/test/contrib/test_automate_soft_dtw.py @@ -0,0 +1,82 @@ +# 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 + +import importlib.util +from pathlib import Path + +import pytest +import torch + + +def _load_soft_dtw_module(): + module_path = Path(__file__).parents[2] / "isaaclab_tasks" / "contrib" / "automate" / "soft_dtw_cuda.py" + spec = importlib.util.spec_from_file_location("automate_soft_dtw_under_test", module_path) + module = importlib.util.module_from_spec(spec) + assert spec.loader is not None + spec.loader.exec_module(module) + return module + + +def test_soft_dtw_use_cuda_does_not_require_numba(): + soft_dtw = _load_soft_dtw_module() + criterion = soft_dtw.SoftDTW(use_cuda=True, device="cuda", gamma=0.01) + + x = torch.zeros((1, 2, 3), dtype=torch.float32) + y = torch.zeros((1, 2, 3), dtype=torch.float32) + + assert criterion(x, y).shape == (1,) + + +def test_soft_dtw_hard_dtw_value(): + soft_dtw = _load_soft_dtw_module() + criterion = soft_dtw.SoftDTW(use_cuda=False, device="cpu", gamma=0.0) + + x = torch.tensor([[[0.0], [1.0]]]) + y = torch.tensor([[[0.0], [2.0]]]) + + assert criterion(x, y) == pytest.approx(torch.tensor([1.0])) + + +def test_normalized_soft_dtw_identical_sequences_are_zero(): + soft_dtw = _load_soft_dtw_module() + criterion = soft_dtw.SoftDTW(use_cuda=True, device="cuda", gamma=0.1, normalize=True) + + x = torch.tensor([[[0.0, 0.0], [1.0, 0.5], [2.0, 1.0]]]) + + assert criterion(x, x) == pytest.approx(torch.zeros(1), abs=1e-6) + + +def test_soft_dtw_forward_with_lengths_matches_unpadded_calls(): + soft_dtw = _load_soft_dtw_module() + criterion = soft_dtw.SoftDTW(use_cuda=False, device="cpu", gamma=0.01) + + torch.manual_seed(11) + x = torch.randn((3, 3, 2), dtype=torch.float32) + y = torch.zeros((3, 5, 2), dtype=torch.float32) + y_lengths = torch.tensor([2, 4, 5], dtype=torch.long) + for batch_id, y_length in enumerate(y_lengths.tolist()): + y[batch_id, :y_length] = torch.randn((y_length, 2), dtype=torch.float32) + + with torch.no_grad(): + actual = criterion.forward_with_lengths(x, y, y_lengths) + expected = torch.cat( + [criterion(x[i : i + 1], y[i : i + 1, : int(y_lengths[i].item())]) for i in range(x.shape[0])] + ) + + assert torch.allclose(actual, expected, atol=1e-6) + + +def test_soft_dtw_backward_produces_finite_gradients(): + soft_dtw = _load_soft_dtw_module() + criterion = soft_dtw.SoftDTW(use_cuda=False, device="cpu", gamma=0.01) + + torch.manual_seed(17) + x = torch.randn((2, 4, 3), dtype=torch.float32, requires_grad=True) + y = torch.randn((2, 5, 3), dtype=torch.float32) + + criterion(x, y).sum().backward() + + assert x.grad is not None + assert torch.isfinite(x.grad).all() From 07e26dc517a012ddf0bab3262e30a37ee9626615 Mon Sep 17 00:00:00 2001 From: Frank Lai NV Date: Tue, 9 Jun 2026 02:18:46 -0400 Subject: [PATCH 30/40] Frlai/fix rnn leapp tracing (#6000) # Description Fixes leapp lstm policy export. Previously it hooked onto structures in rslrl=3.1.2. The update now makes it work for rslrl=5.0.1, same version as the one in the pyproject.toml. Added a regression test to test if rslrl rnns work new test generates a dummy policy with rnn and tests the export. Previous it was assumed that there was one policy with a pretrained checkpoint that had an rnn but turns out there isn't any that by default run rnns so this error slipped through. ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../exporting_policies_with_leapp.rst | 33 +++++++- ...ng_direct_workflow_policies_with_leapp.rst | 6 +- .../leapp/rsl_rl/export.py | 73 ++++++++++++----- .../frlai-fix_rnn_leapp_tracing.rst | 5 ++ .../test/export/test_rsl_rl_export_flow.py | 78 ++++++++++++++++++- 5 files changed, 169 insertions(+), 26 deletions(-) create mode 100644 source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst diff --git a/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst b/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst index 28beaf9ef778..8f645757db00 100644 --- a/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst +++ b/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst @@ -22,7 +22,8 @@ ROS will add direct support for running LEAPP-exported policies in a future rele Prerequisites ------------- -LEAPP requires Python >= 3.8 and PyTorch >= 2.6. Install it with: +This export flow requires ``leapp>=0.5.2``, Python >= 3.8, and PyTorch >= 2.6. Install +LEAPP with: .. tab-set:: :sync-group: os @@ -64,7 +65,7 @@ consumers can run the policy without reconstructing observation ordering, comman targets, or policy feedback loops themselves. For a detailed description of LEAPP's generated artifacts and APIs, refer to the -`LEAPP documentation `__. +`LEAPP documentation `_. Exporting a Policy @@ -279,6 +280,34 @@ simulation without the training infrastructure. This is the Isaac Lab deployment LEAPP-exported policies and is useful for validating that the packaged policy still behaves correctly when driven through the deployment stack instead of the training stack. +Run the deployment script with the task name and the exported LEAPP ``.yaml`` file. + +By default, Isaac Lab launches headless when no visualization option is selected. If you expect +to see the policy running in a viewport, pass a visualization option such as ``--viz kit``: + +.. tab-set:: + :sync-group: os + + .. tab-item:: :icon:`fa-brands fa-linux` Linux + :sync: linux + + .. code-block:: bash + + ./isaaclab.sh -p scripts/reinforcement_learning/leapp/deploy.py \ + --task \ + --leapp_model \ + --viz kit + + .. tab-item:: :icon:`fa-brands fa-windows` Windows + :sync: windows + + .. code-block:: batch + + isaaclab.bat -p scripts\reinforcement_learning\leapp\deploy.py ^ + --task ^ + --leapp_model ^ + --viz kit + For Direct workflow policies, see the :doc:`Direct workflow LEAPP export tutorial `. That guide shows how to add LEAPP annotations to a direct RL environment so it can be diff --git a/docs/source/tutorials/06_exporting/exporting_direct_workflow_policies_with_leapp.rst b/docs/source/tutorials/06_exporting/exporting_direct_workflow_policies_with_leapp.rst index ab5b8731c05f..e4ea57081d29 100644 --- a/docs/source/tutorials/06_exporting/exporting_direct_workflow_policies_with_leapp.rst +++ b/docs/source/tutorials/06_exporting/exporting_direct_workflow_policies_with_leapp.rst @@ -8,6 +8,9 @@ LEAPP. If your policy is manager-based, use the :doc:`manager-based LEAPP export guide ` instead. +For background on LEAPP concepts, supported node patterns, state feedback, and +runtime validation, see the `LEAPP documentation `__. + Overview ~~~~~~~~ @@ -23,7 +26,8 @@ This tutorial uses ``scripts/tutorials/06_deploy/anymal_c_env.py`` as a concrete example of adding LEAPP annotations to a Direct workflow environment. Apply the same annotation pattern to your own Direct RL environment. -Before exporting, install LEAPP into the Isaac Lab Python environment: +This export flow requires ``leapp>=0.5.2``. Before exporting, install LEAPP into +the Isaac Lab Python environment: .. tab-set:: :sync-group: os diff --git a/scripts/reinforcement_learning/leapp/rsl_rl/export.py b/scripts/reinforcement_learning/leapp/rsl_rl/export.py index fedda81cb961..c32f08b9f835 100644 --- a/scripts/reinforcement_learning/leapp/rsl_rl/export.py +++ b/scripts/reinforcement_learning/leapp/rsl_rl/export.py @@ -26,8 +26,14 @@ import cli_args # isort: skip +RSL_RL_MIN_VERSION = "5.0.1" _RUNTIME_IMPORTS_LOADED = False +# Keep heavy/runtime-sensitive imports out of module import time. The CLI needs +# to parse launcher arguments and start Isaac Sim/Kit before importing torch, +# LEAPP, RSL-RL, and task modules; importing them earlier has caused launcher +# import-order failures. ``_load_runtime_dependencies()`` populates these +# globals immediately before export execution. torch = None leapp = None annotate = None @@ -43,6 +49,7 @@ get_published_pretrained_checkpoint = None get_checkpoint_path = None hydra_task_config = None +installed_version = None def create_arg_parser() -> argparse.ArgumentParser: @@ -117,6 +124,7 @@ def _load_runtime_dependencies() -> None: global annotate, leapp, torch global DistillationRunner, ManagerBasedRLEnv, OnPolicyRunner, RslRlVecEnvWrapper, get_checkpoint_path, gym global ensure_env_spec_id, get_published_pretrained_checkpoint, handle_deprecated_rsl_rl_cfg, hydra_task_config + global installed_version global patch_env_for_export, retrieve_file_path if _RUNTIME_IMPORTS_LOADED: @@ -130,6 +138,7 @@ def _load_runtime_dependencies() -> None: import gymnasium as gym_module import torch as torch_module + from packaging import version as packaging_version_module from rsl_rl.runners import DistillationRunner as DistillationRunnerCls from rsl_rl.runners import OnPolicyRunner as OnPolicyRunnerCls @@ -152,6 +161,13 @@ def _load_runtime_dependencies() -> None: from isaaclab_tasks.utils import get_checkpoint_path as get_checkpoint_path_fn from isaaclab_tasks.utils.hydra import hydra_task_config as hydra_task_config_fn + installed_version = metadata.version("rsl-rl-lib") + if packaging_version_module.parse(installed_version) < packaging_version_module.parse(RSL_RL_MIN_VERSION): + print( + f"[WARNING] LEAPP RSL-RL export is validated with rsl-rl-lib {RSL_RL_MIN_VERSION} or newer. " + f"Installed version is '{installed_version}'." + ) + torch = torch_module leapp = leapp_module annotate = annotate_module @@ -170,25 +186,43 @@ def _load_runtime_dependencies() -> None: _RUNTIME_IMPORTS_LOADED = True -installed_version = metadata.version("rsl-rl-lib") +def get_actor_memory_module(policy): + """Return the actor-side RNN module for supported RSL-RL recurrent policies.""" + if hasattr(policy, "rnn"): + return policy.rnn + return None + +def is_actor_recurrent_policy(policy) -> bool: + """Return whether the actor policy has a supported recurrent state container.""" + return bool(getattr(policy, "is_recurrent", False) and get_actor_memory_module(policy) is not None) -def get_actor_memory_module(policy_nn): - """Return the actor-side recurrent memory module when the policy exposes one.""" - if hasattr(policy_nn, "memory_a"): - return policy_nn.memory_a - if hasattr(policy_nn, "memory_s"): - return policy_nn.memory_s - return None + +def get_actor_hidden_state(policy): + """Return the actor-side recurrent hidden state for supported RSL-RL policy APIs.""" + if hasattr(policy, "get_hidden_state"): + return policy.get_hidden_state() + memory = get_actor_memory_module(policy) + return None if memory is None else getattr(memory, "hidden_state", None) + + +def set_actor_hidden_state(policy, actor_hidden) -> None: + """Assign the actor-side recurrent hidden state for supported RSL-RL policy APIs.""" + memory = get_actor_memory_module(policy) + if memory is not None: + memory.hidden_state = actor_hidden -def ensure_actor_hidden_state_initialized(policy_nn, batch_size: int, device, dtype): +def ensure_actor_hidden_state_initialized(policy, batch_size: int, device, dtype): """Initialize and return the actor hidden state when a recurrent policy has not created it yet.""" - actor_state, _ = policy_nn.get_hidden_states() + # ``torch`` is a lazy runtime global populated by ``_load_runtime_dependencies()`` + # after Isaac Sim launches and before export calls this helper. + assert torch is not None + actor_state = get_actor_hidden_state(policy) if actor_state is not None: return actor_state - memory = get_actor_memory_module(policy_nn) + memory = get_actor_memory_module(policy) if memory is None or not hasattr(memory, "rnn"): return None @@ -199,7 +233,7 @@ def ensure_actor_hidden_state_initialized(policy_nn, batch_size: int, device, dt actor_state = (zeros.clone(), zeros.clone()) else: actor_state = zeros - memory.hidden_state = actor_state + set_actor_hidden_state(policy, actor_state) return actor_state @@ -298,7 +332,6 @@ def export_rsl_rl_agent( runner.load(resume_path) policy = runner.get_inference_policy(device=env.unwrapped.device) - policy_nn = getattr(policy, "__self__", None) if args_cli.export_save_path is not None: save_path = args_cli.export_save_path @@ -316,25 +349,23 @@ def export_rsl_rl_agent( for _ in range(max(args_cli.validation_steps, 2)): with torch.inference_mode(): - if policy_nn is not None and getattr(policy_nn, "is_recurrent", False): + if is_actor_recurrent_policy(policy): actor_hidden = ensure_actor_hidden_state_initialized( - policy_nn, + policy, batch_size=env.num_envs, device=env.unwrapped.device, - dtype=next(policy_nn.parameters()).dtype, + dtype=next(policy.parameters()).dtype, ) registered_state = annotate.state_tensors( policy_node_name, state_dict_from_actor_hidden(actor_hidden), ) - actor_memory = get_actor_memory_module(policy_nn) - if actor_memory is not None: - actor_memory.hidden_state = actor_hidden_from_registered(registered_state, actor_hidden) + set_actor_hidden_state(policy, actor_hidden_from_registered(registered_state, actor_hidden)) actions = policy(obs) - if policy_nn is not None and getattr(policy_nn, "is_recurrent", False): - actor_hidden_after = policy_nn.get_hidden_states()[0] + if is_actor_recurrent_policy(policy): + actor_hidden_after = get_actor_hidden_state(policy) annotate.update_state( policy_node_name, state_dict_from_actor_hidden(actor_hidden_after), diff --git a/source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst b/source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst new file mode 100644 index 000000000000..df82ca280f65 --- /dev/null +++ b/source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed LEAPP export of RSL-RL recurrent policies to preserve actor hidden + state across supported RSL-RL policy APIs. diff --git a/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py b/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py index 9ba5e85297c7..1dde9ceb1615 100644 --- a/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py +++ b/source/isaaclab_rl/test/export/test_rsl_rl_export_flow.py @@ -16,10 +16,13 @@ import shutil import subprocess import sys +import types from pathlib import Path import pytest +torch = pytest.importorskip("torch") + # Root of the repository (three levels up from this file). _REPO_ROOT = Path(__file__).resolve().parents[4] _EXPORT_SCRIPT = _REPO_ROOT / "scripts" / "reinforcement_learning" / "leapp" / "rsl_rl" / "export.py" @@ -136,19 +139,70 @@ def _leapp_log_tail(export_dir: str) -> str: def _load_export_module(): """Load the LEAPP RSL-RL export script as an importable module.""" module = sys.modules.get(_EXPORT_MODULE_NAME) - if module is not None: + if module is not None and hasattr(module, "ensure_actor_hidden_state_initialized"): return module + sys.modules.pop(_EXPORT_MODULE_NAME, None) spec = importlib.util.spec_from_file_location(_EXPORT_MODULE_NAME, _EXPORT_SCRIPT) if spec is None or spec.loader is None: raise ImportError(f"Could not create module spec for {_EXPORT_SCRIPT}") module = importlib.util.module_from_spec(spec) sys.modules[_EXPORT_MODULE_NAME] = module - spec.loader.exec_module(module) + original_modules = { + name: sys.modules.get(name) for name in ("isaaclab", "isaaclab.app", "isaaclab_tasks", "isaaclab_tasks.utils") + } + isaaclab_module = types.ModuleType("isaaclab") + isaaclab_app_module = types.ModuleType("isaaclab.app") + isaaclab_tasks_module = types.ModuleType("isaaclab_tasks") + isaaclab_tasks_utils_module = types.ModuleType("isaaclab_tasks.utils") + + class _AppLauncher: + @staticmethod + def add_app_launcher_args(parser): + return None + + setattr(isaaclab_app_module, "AppLauncher", _AppLauncher) + setattr(isaaclab_tasks_utils_module, "fold_preset_tokens", lambda args: args) + setattr(isaaclab_tasks_utils_module, "setup_preset_cli", lambda parser, argv=None: parser.parse_known_args(argv)) + sys.modules["isaaclab"] = isaaclab_module + sys.modules["isaaclab.app"] = isaaclab_app_module + sys.modules["isaaclab_tasks"] = isaaclab_tasks_module + sys.modules["isaaclab_tasks.utils"] = isaaclab_tasks_utils_module + try: + spec.loader.exec_module(module) + finally: + for name, original_module in original_modules.items(): + if original_module is None: + sys.modules.pop(name, None) + else: + sys.modules[name] = original_module + setattr(module, "torch", torch) return module +class _ModularRNN(torch.nn.Module): + """Minimal RSL-RL 5.x RNN wrapper shape.""" + + def __init__(self): + super().__init__() + self.rnn = torch.nn.LSTM(input_size=2, hidden_size=4, num_layers=2) + self.hidden_state = None + + +class _ModularRecurrentPolicy(torch.nn.Module): + """Minimal RSL-RL 5.x RNNModel shape.""" + + is_recurrent = True + + def __init__(self): + super().__init__() + self.rnn = _ModularRNN() + + def get_hidden_state(self): + return self.rnn.hidden_state + + @contextlib.contextmanager def _clean_hydra_argv(): """Temporarily hide pytest arguments from Hydra config resolution.""" @@ -242,6 +296,26 @@ def _run_export_batch_entrypoint() -> None: _run_export_batch(tasks) +def test_recurrent_state_helpers_support_modular_rnn_model_lstm(): + """Verify LSTM state registration helpers support RSL-RL 5.x RNNModel.""" + export_module = _load_export_module() + policy = _ModularRecurrentPolicy() + + actor_state = export_module.ensure_actor_hidden_state_initialized( + policy, batch_size=1, device=torch.device("cpu"), dtype=torch.float32 + ) + registered_state = tuple(tensor + 1.0 for tensor in actor_state) + export_module.set_actor_hidden_state( + policy, + export_module.actor_hidden_from_registered(registered_state, actor_state), + ) + + assert export_module.is_actor_recurrent_policy(policy) + assert export_module.get_actor_memory_module(policy) is policy.rnn + assert export_module.get_actor_hidden_state(policy) is registered_state + assert policy.rnn.hidden_state is registered_state + + @pytest.mark.parametrize("task_names", _task_batches(TASKS), ids=_batch_id) def test_export_flow(task_names: list[str]): """Run export.py for a task batch and assert the expected artifacts are created.""" From 282bddc2047ee298db6a64ae7f5583b6035b2813 Mon Sep 17 00:00:00 2001 From: "isaaclab-bot[bot]" <282401363+isaaclab-bot[bot]@users.noreply.github.com> Date: Tue, 9 Jun 2026 06:26:13 +0000 Subject: [PATCH 31/40] [CI][Auto Version Bump] Compile changelog fragments (schedule) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Bumped packages: - isaaclab: 6.6.0 → 6.6.1 - isaaclab_newton: 0.15.3 → 0.15.4 - isaaclab_ov: 0.4.3 → 0.4.4 - isaaclab_ovphysx: 3.0.2 → 3.0.3 - isaaclab_physx: 1.1.4 → 1.1.5 - isaaclab_rl: 0.6.0 → 0.6.1 - isaaclab_tasks: 4.0.0 → 5.0.0 --- .../changelog.d/fix-env-del-shutdown.rst | 4 --- .../fix-kit-wheeled-robots-optional.rst | 9 ----- .../fix-mdl-module-dependencies.rst | 4 --- .../lgulich-leapp-root-quat-gravity.rst | 6 ---- .../mhaiderbhai-merge-lift-tasks.skip | 1 - .../nicolasm-ppisp-extension-dependency.rst | 4 --- .../changelog.d/pbarejko-carb-env-shim.skip | 7 ---- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 20 +++++++++++ source/isaaclab/pyproject.toml | 2 +- .../huidongc-fix-incorrect-camera-pose.rst | 4 --- .../nicolasm-ppisp-extension-dependency.rst | 4 --- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 10 ++++++ source/isaaclab_newton/pyproject.toml | 2 +- .../nicolasm-ppisp-extension-dependency.rst | 4 --- source/isaaclab_ov/config/extension.toml | 2 +- source/isaaclab_ov/docs/CHANGELOG.rst | 9 +++++ source/isaaclab_ov/pyproject.toml | 2 +- .../antoiner-ovphysx-runtime-guard.rst | 5 --- source/isaaclab_ovphysx/config/extension.toml | 2 +- source/isaaclab_ovphysx/docs/CHANGELOG.rst | 10 ++++++ source/isaaclab_ovphysx/pyproject.toml | 2 +- .../nicolasm-ppisp-extension-dependency.rst | 4 --- source/isaaclab_physx/config/extension.toml | 2 +- source/isaaclab_physx/docs/CHANGELOG.rst | 9 +++++ source/isaaclab_physx/pyproject.toml | 2 +- .../fix-skrl-jax-multihost-import.rst | 6 ---- .../frlai-fix_rnn_leapp_tracing.rst | 5 --- .../lgulich-leapp-root-quat-gravity.skip | 0 .../mhaiderbhai-merge-lift-tasks.skip | 1 - source/isaaclab_rl/config/extension.toml | 2 +- source/isaaclab_rl/docs/CHANGELOG.rst | 13 +++++++ source/isaaclab_rl/pyproject.toml | 2 +- .../fix-automate-collision-stack.rst | 5 --- .../fix-automate-numba-constraints.rst | 5 --- .../mhaiderbhai-merge-lift-tasks.major.rst | 27 -------------- source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 36 +++++++++++++++++++ source/isaaclab_tasks/pyproject.toml | 2 +- 40 files changed, 121 insertions(+), 119 deletions(-) delete mode 100644 source/isaaclab/changelog.d/fix-env-del-shutdown.rst delete mode 100644 source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst delete mode 100644 source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst delete mode 100644 source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst delete mode 100644 source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip delete mode 100644 source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst delete mode 100644 source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip delete mode 100644 source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst delete mode 100644 source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst delete mode 100644 source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst delete mode 100644 source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst delete mode 100644 source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst delete mode 100644 source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst delete mode 100644 source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst delete mode 100644 source/isaaclab_rl/changelog.d/lgulich-leapp-root-quat-gravity.skip delete mode 100644 source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip delete mode 100644 source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst delete mode 100644 source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst delete mode 100644 source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst diff --git a/source/isaaclab/changelog.d/fix-env-del-shutdown.rst b/source/isaaclab/changelog.d/fix-env-del-shutdown.rst deleted file mode 100644 index ef77e3fea523..000000000000 --- a/source/isaaclab/changelog.d/fix-env-del-shutdown.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Prevented environment destructors from emitting cleanup tracebacks after Python import shutdown begins. diff --git a/source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst b/source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst deleted file mode 100644 index c80cc2d0d19e..000000000000 --- a/source/isaaclab/changelog.d/fix-kit-wheeled-robots-optional.rst +++ /dev/null @@ -1,9 +0,0 @@ -Fixed -^^^^^ - -* Fixed the ``isaaclab.python.kit`` GUI experience failing to start with a Kit - dependency-solver error on Isaac Sim builds that do not ship - ``isaacsim.robot.experimental.wheeled_robots`` or - ``isaacsim.robot.wheeled_robots.nodes``. These extensions are not imported by - Isaac Lab and are now declared optional, so the experience loads regardless of - the Isaac Sim build. diff --git a/source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst b/source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst deleted file mode 100644 index 930fd7b83a69..000000000000 --- a/source/isaaclab/changelog.d/fix-mdl-module-dependencies.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed local asset retrieval for MDL files that import sibling MDL modules, such as Hospital materials importing OmniUe4 modules. diff --git a/source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst b/source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst deleted file mode 100644 index 92af9a52251c..000000000000 --- a/source/isaaclab/changelog.d/lgulich-leapp-root-quat-gravity.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed LEAPP export of :func:`isaaclab.envs.mdp.projected_gravity` to expose - root orientation as the graph input and compute projected gravity inside the - exported graph. diff --git a/source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip b/source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip deleted file mode 100644 index f91aafa24891..000000000000 --- a/source/isaaclab/changelog.d/mhaiderbhai-merge-lift-tasks.skip +++ /dev/null @@ -1 +0,0 @@ -Test-only: updated lift task IDs in tests to match the consolidated/renamed environments. diff --git a/source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst deleted file mode 100644 index a7d4ec21b507..000000000000 --- a/source/isaaclab/changelog.d/nicolasm-ppisp-extension-dependency.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed the ``isaaclab[all]`` extra to include ``isaaclab_ppisp`` as a peer extension. diff --git a/source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip b/source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip deleted file mode 100644 index 3e85fdd60bc6..000000000000 --- a/source/isaaclab/changelog.d/pbarejko-carb-env-shim.skip +++ /dev/null @@ -1,7 +0,0 @@ -Fixed -^^^^^ - -* Fixed intermittent ``getenv`` SIGSEGVs in Docker CI by copying the - Carbonite ``libcarb.env.shim.so`` out of the Isaac Sim install tree and - preloading it via ``/etc/ld.so.preload`` at image-build time, instead of - vendoring a prebuilt shim binary in the repo. diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index adfe1a7e81f3..95de722bdaa4 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "6.6.0" +version = "6.6.1" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 2f4dcad4180d..301f862411d9 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,26 @@ Changelog --------- +6.6.1 (2026-06-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed the ``isaaclab[all]`` extra to include ``isaaclab_ppisp`` as a peer extension. +* Fixed LEAPP export of :func:`isaaclab.envs.mdp.projected_gravity` to expose + root orientation as the graph input and compute projected gravity inside the + exported graph. +* Fixed local asset retrieval for MDL files that import sibling MDL modules, such as Hospital materials importing OmniUe4 modules. +* Prevented environment destructors from emitting cleanup tracebacks after Python import shutdown begins. +* Fixed the ``isaaclab.python.kit`` GUI experience failing to start with a Kit + dependency-solver error on Isaac Sim builds that do not ship + ``isaacsim.robot.experimental.wheeled_robots`` or + ``isaacsim.robot.wheeled_robots.nodes``. These extensions are not imported by + Isaac Lab and are now declared optional, so the experience loads regardless of + the Isaac Sim build. + + 6.6.0 (2026-06-08) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/pyproject.toml b/source/isaaclab/pyproject.toml index fe9296b5a721..4f2a4859a3f3 100644 --- a/source/isaaclab/pyproject.toml +++ b/source/isaaclab/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab" -version = "6.6.0" +version = "6.6.1" description = "Extension providing main framework interfaces and abstractions for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst b/source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst deleted file mode 100644 index 9fc4300916b8..000000000000 --- a/source/isaaclab_newton/changelog.d/huidongc-fix-incorrect-camera-pose.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed incorrect camera pose in :class:`~isaaclab_newton.sim.views.NewtonSiteFrameView`. diff --git a/source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst deleted file mode 100644 index 0715b7ffb75e..000000000000 --- a/source/isaaclab_newton/changelog.d/nicolasm-ppisp-extension-dependency.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed Newton package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index b87c4935290f..86e585e22b66 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.15.3" +version = "0.15.4" # Description title = "Newton simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index 3f87dce484e1..7adca70938f4 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.15.4 (2026-06-09) +~~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed Newton package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. +* Fixed incorrect camera pose in :class:`~isaaclab_newton.sim.views.NewtonSiteFrameView`. + + 0.15.3 (2026-06-08) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/pyproject.toml b/source/isaaclab_newton/pyproject.toml index 8903ed7ed9e1..4d025ad7530f 100644 --- a/source/isaaclab_newton/pyproject.toml +++ b/source/isaaclab_newton/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_newton" -version = "0.15.3" +version = "0.15.4" description = "Extension providing IsaacLab with Newton specific abstractions." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst deleted file mode 100644 index 45cef4e3fec5..000000000000 --- a/source/isaaclab_ov/changelog.d/nicolasm-ppisp-extension-dependency.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed OVRTX package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. diff --git a/source/isaaclab_ov/config/extension.toml b/source/isaaclab_ov/config/extension.toml index 5254712507b7..886027943eaf 100644 --- a/source/isaaclab_ov/config/extension.toml +++ b/source/isaaclab_ov/config/extension.toml @@ -1,5 +1,5 @@ [package] -version = "0.4.3" +version = "0.4.4" title = "Omniverse renderers for IsaacLab" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." readme = "docs/README.md" diff --git a/source/isaaclab_ov/docs/CHANGELOG.rst b/source/isaaclab_ov/docs/CHANGELOG.rst index d9caa2072081..09cbc0a3bf76 100644 --- a/source/isaaclab_ov/docs/CHANGELOG.rst +++ b/source/isaaclab_ov/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +0.4.4 (2026-06-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed OVRTX package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. + + 0.4.3 (2026-06-06) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ov/pyproject.toml b/source/isaaclab_ov/pyproject.toml index b9f686f8a3fe..faf9753bfc20 100644 --- a/source/isaaclab_ov/pyproject.toml +++ b/source/isaaclab_ov/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_ov" -version = "0.4.3" +version = "0.4.4" description = "Extension providing Omniverse renderers (OVRTX, ovphysx, etc.) for tiled camera rendering." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst b/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst deleted file mode 100644 index ed997b81bb0d..000000000000 --- a/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-runtime-guard.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Added an actionable install error when the optional ``ovphysx`` runtime wheel - is missing from the :mod:`isaaclab_ovphysx` backend. diff --git a/source/isaaclab_ovphysx/config/extension.toml b/source/isaaclab_ovphysx/config/extension.toml index f33577e0ae85..1de096349c5b 100644 --- a/source/isaaclab_ovphysx/config/extension.toml +++ b/source/isaaclab_ovphysx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "3.0.2" +version = "3.0.3" # Description title = "OvPhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_ovphysx/docs/CHANGELOG.rst b/source/isaaclab_ovphysx/docs/CHANGELOG.rst index 33a729c3dff5..277988bd61f0 100644 --- a/source/isaaclab_ovphysx/docs/CHANGELOG.rst +++ b/source/isaaclab_ovphysx/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +3.0.3 (2026-06-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Added an actionable install error when the optional ``ovphysx`` runtime wheel + is missing from the :mod:`isaaclab_ovphysx` backend. + + 3.0.2 (2026-06-05) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_ovphysx/pyproject.toml b/source/isaaclab_ovphysx/pyproject.toml index 953c4e568efc..2d8a8515decb 100644 --- a/source/isaaclab_ovphysx/pyproject.toml +++ b/source/isaaclab_ovphysx/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_ovphysx" -version = "3.0.2" +version = "3.0.3" description = "Extension providing IsaacLab with ovphysx/TensorBindingsAPI specific abstractions." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst b/source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst deleted file mode 100644 index 9b00c1c5d440..000000000000 --- a/source/isaaclab_physx/changelog.d/nicolasm-ppisp-extension-dependency.rst +++ /dev/null @@ -1,4 +0,0 @@ -Fixed -^^^^^ - -* Fixed Isaac RTX package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. diff --git a/source/isaaclab_physx/config/extension.toml b/source/isaaclab_physx/config/extension.toml index 785fb7b58567..54bf138024f0 100644 --- a/source/isaaclab_physx/config/extension.toml +++ b/source/isaaclab_physx/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.1.4" +version = "1.1.5" # Description title = "PhysX simulation interfaces for IsaacLab core package" diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index d5797e4719ac..5a53c00f5848 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +1.1.5 (2026-06-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed Isaac RTX package resolution so ``isaaclab_ppisp`` is only required when camera ``isp_cfg`` is set. + + 1.1.4 (2026-06-06) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_physx/pyproject.toml b/source/isaaclab_physx/pyproject.toml index c5b6ad86b9ed..f513f84a93ae 100644 --- a/source/isaaclab_physx/pyproject.toml +++ b/source/isaaclab_physx/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_physx" -version = "1.1.4" +version = "1.1.5" description = "Extension providing IsaacLab with PhysX specific abstractions." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst b/source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst deleted file mode 100644 index 52048ef93974..000000000000 --- a/source/isaaclab_rl/changelog.d/fix-skrl-jax-multihost-import.rst +++ /dev/null @@ -1,6 +0,0 @@ -Fixed -^^^^^ - -* Fixed :func:`~isaaclab_rl.skrl.SkrlVecEnvWrapper` failing to import the JAX wrapper on recent JAX - versions by preloading the ``jax.experimental.multihost_utils`` submodule that skrl's distributed - models reference without importing. diff --git a/source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst b/source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst deleted file mode 100644 index df82ca280f65..000000000000 --- a/source/isaaclab_rl/changelog.d/frlai-fix_rnn_leapp_tracing.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Fixed LEAPP export of RSL-RL recurrent policies to preserve actor hidden - state across supported RSL-RL policy APIs. diff --git a/source/isaaclab_rl/changelog.d/lgulich-leapp-root-quat-gravity.skip b/source/isaaclab_rl/changelog.d/lgulich-leapp-root-quat-gravity.skip deleted file mode 100644 index e69de29bb2d1..000000000000 diff --git a/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip b/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip deleted file mode 100644 index f91aafa24891..000000000000 --- a/source/isaaclab_rl/changelog.d/mhaiderbhai-merge-lift-tasks.skip +++ /dev/null @@ -1 +0,0 @@ -Test-only: updated lift task IDs in tests to match the consolidated/renamed environments. diff --git a/source/isaaclab_rl/config/extension.toml b/source/isaaclab_rl/config/extension.toml index 9a0e803e0419..b023dc84c310 100644 --- a/source/isaaclab_rl/config/extension.toml +++ b/source/isaaclab_rl/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.6.0" +version = "0.6.1" # Description title = "Isaac Lab RL" diff --git a/source/isaaclab_rl/docs/CHANGELOG.rst b/source/isaaclab_rl/docs/CHANGELOG.rst index ab1a9451aec6..cd9a3f934b59 100644 --- a/source/isaaclab_rl/docs/CHANGELOG.rst +++ b/source/isaaclab_rl/docs/CHANGELOG.rst @@ -1,6 +1,19 @@ Changelog --------- +0.6.1 (2026-06-09) +~~~~~~~~~~~~~~~~~~ + +Fixed +^^^^^ + +* Fixed :func:`~isaaclab_rl.skrl.SkrlVecEnvWrapper` failing to import the JAX wrapper on recent JAX + versions by preloading the ``jax.experimental.multihost_utils`` submodule that skrl's distributed + models reference without importing. +* Fixed LEAPP export of RSL-RL recurrent policies to preserve actor hidden + state across supported RSL-RL policy APIs. + + 0.6.0 (2026-06-04) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_rl/pyproject.toml b/source/isaaclab_rl/pyproject.toml index 7d4080256971..348278bd75b8 100644 --- a/source/isaaclab_rl/pyproject.toml +++ b/source/isaaclab_rl/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_rl" -version = "0.6.0" +version = "0.6.1" description = "Extension containing reinforcement learning related utilities." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] diff --git a/source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst b/source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst deleted file mode 100644 index f10f973072fe..000000000000 --- a/source/isaaclab_tasks/changelog.d/fix-automate-collision-stack.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Increased the AutoMate assembly and disassembly PhysX GPU collision stack to avoid dropped contacts at the default 128 environments. -* Updated AutoMate run helpers and docs to reject placeholder assembly IDs before launching simulation. diff --git a/source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst b/source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst deleted file mode 100644 index 85dff4de4ee2..000000000000 --- a/source/isaaclab_tasks/changelog.d/fix-automate-numba-constraints.rst +++ /dev/null @@ -1,5 +0,0 @@ -Fixed -^^^^^ - -* Removed AutoMate's Numba dependency by replacing the SoftDTW helper with a - Torch implementation. diff --git a/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst b/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst deleted file mode 100644 index b129f035d180..000000000000 --- a/source/isaaclab_tasks/changelog.d/mhaiderbhai-merge-lift-tasks.major.rst +++ /dev/null @@ -1,27 +0,0 @@ -Changed -^^^^^^^ - -* **Breaking:** Consolidated the rigid and soft Franka lifting tasks into a single - :mod:`isaaclab_tasks.core.lift` package. The former ``isaaclab_tasks.core.lift_franka_soft`` - package moved under :mod:`isaaclab_tasks.core.lift.config.franka_soft`, alongside the existing - rigid ``franka`` config, to keep the rigid and soft variants separated. Update imports such as - ``from isaaclab_tasks.core.lift_franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg`` to - ``from isaaclab_tasks.core.lift.config.franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg``. - The deformable MDP terms were merged into the shared :mod:`isaaclab_tasks.core.lift.mdp` package - (rather than a separate per-variant ``mdp``); import them from there, e.g. - ``from isaaclab_tasks.core.lift.mdp import deformable_lifted``. -* **Breaking:** Renamed the lift Gym environment IDs to drop the ``-v0`` version suffix. Update - ``gym.make`` / ``--task`` calls: - - * ``Isaac-Lift-Cube-Franka-v0`` → ``Isaac-Lift-Cube-Franka``. - * ``Isaac-Lift-Cube-Franka-Play-v0`` → ``Isaac-Lift-Cube-Franka-Play``. - * ``Isaac-Lift-Soft-Franka-v0`` → ``Isaac-Lift-Soft-Franka``. - * ``Isaac-Lift-Cloth-Franka-v0`` → ``Isaac-Lift-Cloth-Franka``. - -Fixed -^^^^^ - -* Renamed the ``Isaac-Lift-Cloth-Franka`` physics preset from the misspelled ``newton_mjwarp_vdb`` - to ``newton_mjwarp_vbd``, matching the soft-body task and the underlying VBD solver. The cloth - ``RewardsCfg``, which duplicated the soft task's rewards verbatim, is now inherited instead of - redefined. diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index 82e42b2adf75..404d651bf821 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.0.0" +version = "5.0.0" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index ca0b9005f4d6..bc6022aee4b0 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,42 @@ Changelog --------- +5.0.0 (2026-06-09) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* **Breaking:** Consolidated the rigid and soft Franka lifting tasks into a single + :mod:`isaaclab_tasks.core.lift` package. The former ``isaaclab_tasks.core.lift_franka_soft`` + package moved under :mod:`isaaclab_tasks.core.lift.config.franka_soft`, alongside the existing + rigid ``franka`` config, to keep the rigid and soft variants separated. Update imports such as + ``from isaaclab_tasks.core.lift_franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg`` to + ``from isaaclab_tasks.core.lift.config.franka_soft.franka_soft_env_cfg import FrankaSoftEnvCfg``. + The deformable MDP terms were merged into the shared :mod:`isaaclab_tasks.core.lift.mdp` package + (rather than a separate per-variant ``mdp``); import them from there, e.g. + ``from isaaclab_tasks.core.lift.mdp import deformable_lifted``. +* **Breaking:** Renamed the lift Gym environment IDs to drop the ``-v0`` version suffix. Update + ``gym.make`` / ``--task`` calls: + + * ``Isaac-Lift-Cube-Franka-v0`` → ``Isaac-Lift-Cube-Franka``. + * ``Isaac-Lift-Cube-Franka-Play-v0`` → ``Isaac-Lift-Cube-Franka-Play``. + * ``Isaac-Lift-Soft-Franka-v0`` → ``Isaac-Lift-Soft-Franka``. + * ``Isaac-Lift-Cloth-Franka-v0`` → ``Isaac-Lift-Cloth-Franka``. + +Fixed +^^^^^ + +* Increased the AutoMate assembly and disassembly PhysX GPU collision stack to avoid dropped contacts at the default 128 environments. +* Updated AutoMate run helpers and docs to reject placeholder assembly IDs before launching simulation. +* Renamed the ``Isaac-Lift-Cloth-Franka`` physics preset from the misspelled ``newton_mjwarp_vdb`` + to ``newton_mjwarp_vbd``, matching the soft-body task and the underlying VBD solver. The cloth + ``RewardsCfg``, which duplicated the soft task's rewards verbatim, is now inherited instead of + redefined. +* Removed AutoMate's Numba dependency by replacing the SoftDTW helper with a + Torch implementation. + + 4.0.0 (2026-06-07) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/pyproject.toml b/source/isaaclab_tasks/pyproject.toml index 613310dacb62..854033b45a81 100644 --- a/source/isaaclab_tasks/pyproject.toml +++ b/source/isaaclab_tasks/pyproject.toml @@ -9,7 +9,7 @@ build-backend = "setuptools.build_meta" [project] name = "isaaclab_tasks" -version = "4.0.0" +version = "5.0.0" description = "Extension containing suite of environments for robot learning." license = {text = "BSD-3-Clause"} authors = [{name = "Isaac Lab Project Developers"}] From 563388a6677bbca2b7155b38223d88682880e17a Mon Sep 17 00:00:00 2001 From: ooctipus Date: Tue, 9 Jun 2026 00:27:03 -0700 Subject: [PATCH 32/40] Fix Newton rigid object root state writers (#6004) ## Summary - call Newton rigid-object pose and velocity helper methods with explicit keyword arguments from deprecated root-state writer wrappers - align the Newton rigid-object wrappers with the keyword-only helper signatures and the other physics backends - add a Newton changelog fragment ## Tests - `git diff --cached --check` before commit - syntax parsed modified Python file with `ast.parse` - Not run: Isaac Sim tests in this local environment are missing Python dependency `lazy_loader` --- .../changelog.d/fix-rigid-object-state-writers.rst | 5 +++++ .../assets/rigid_object/rigid_object.py | 12 ++++++------ 2 files changed, 11 insertions(+), 6 deletions(-) create mode 100644 source/isaaclab_newton/changelog.d/fix-rigid-object-state-writers.rst diff --git a/source/isaaclab_newton/changelog.d/fix-rigid-object-state-writers.rst b/source/isaaclab_newton/changelog.d/fix-rigid-object-state-writers.rst new file mode 100644 index 000000000000..da51c5f943f6 --- /dev/null +++ b/source/isaaclab_newton/changelog.d/fix-rigid-object-state-writers.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed Newton rigid-object deprecated root state writers to call keyword-only + pose and velocity helpers correctly. diff --git a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py index 2709609e0f4f..693a0292c0cf 100644 --- a/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object.py @@ -1117,8 +1117,8 @@ def write_root_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[in ) if isinstance(root_state, wp.array): raise ValueError("The root state must be a torch tensor, not a warp array.") - self.write_root_link_pose_to_sim_index(root_state[:, :7], env_ids=env_ids) - self.write_root_com_velocity_to_sim_index(root_state[:, 7:], env_ids=env_ids) + self.write_root_link_pose_to_sim_index(root_pose=root_state[:, :7], env_ids=env_ids) + self.write_root_com_velocity_to_sim_index(root_velocity=root_state[:, 7:], env_ids=env_ids) def write_root_com_state_to_sim( self, root_state: torch.Tensor, env_ids: Sequence[int] | torch.Tensor | None = None @@ -1133,8 +1133,8 @@ def write_root_com_state_to_sim( ) if isinstance(root_state, wp.array): raise ValueError("The root state must be a torch tensor, not a warp array.") - self.write_root_com_pose_to_sim_index(root_state[:, :7], env_ids=env_ids) - self.write_root_com_velocity_to_sim_index(root_state[:, 7:], env_ids=env_ids) + self.write_root_com_pose_to_sim_index(root_pose=root_state[:, :7], env_ids=env_ids) + self.write_root_com_velocity_to_sim_index(root_velocity=root_state[:, 7:], env_ids=env_ids) def write_root_link_state_to_sim( self, root_state: torch.Tensor, env_ids: Sequence[int] | torch.Tensor | None = None @@ -1149,5 +1149,5 @@ def write_root_link_state_to_sim( ) if isinstance(root_state, wp.array): raise ValueError("The root state must be a torch tensor, not a warp array.") - self.write_root_link_pose_to_sim_index(root_state[:, :7], env_ids=env_ids) - self.write_root_link_velocity_to_sim_index(root_state[:, 7:], env_ids=env_ids) + self.write_root_link_pose_to_sim_index(root_pose=root_state[:, :7], env_ids=env_ids) + self.write_root_link_velocity_to_sim_index(root_velocity=root_state[:, 7:], env_ids=env_ids) From cf615d32e334934ee3939ce66edafc86f5344689 Mon Sep 17 00:00:00 2001 From: rwiltz <165190220+rwiltz@users.noreply.github.com> Date: Tue, 9 Jun 2026 03:52:25 -0400 Subject: [PATCH 33/40] Document non-root Docker volume fix for XR teleop startup (#6060) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Since the non-root Docker migration (#5618, first shipped in 3.0.0-beta2), the container runs as user `isaaclab` (uid/gid 1000) with `HOME=/root`. Persistent mounts at `/root/.local/share/ov/data` that were created by an older root-based image (stale named volumes) or by Docker as auto-created bind-mount dirs are owned by `root`, so the runtime user cannot write the extension-registry cache. For XR teleop this aborts startup with a confusing, seemingly-unrelated error: PermissionError: [Errno 13] Permission denied: '/root/.local/share/ov/data/exts' ... No versions of omni.kit.xr.bundle.generic that satisfies: isaaclab.python.xr.openxr-3.0.0 ... Exiting app because of dependency solver failure... The XR bundle isn't actually missing — the registry never synced because its cache dir couldn't be created. This PR documents the cause and fix: - **`docs/source/how-to/cloudxr_teleoperation.rst`**: adds an admonition to the "Run with Docker" section explaining the failure and the fix (recreate/chown volumes for Compose, pre-create/chown host dirs for single-container). - **`docs/source/deployment/docker.rst`**: warns that non-root prebuilt images need bind-mount host dirs pre-created and chowned to uid/gid 1000, with a copy-paste snippet. Docs-only; no code changes and no changelog fragment (no `source//` package touched). Fixes # (issue) ## Type of change - Documentation update ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- docs/source/deployment/docker.rst | 15 +++++++++ docs/source/how-to/cloudxr_teleoperation.rst | 35 ++++++++++++++++++++ 2 files changed, 50 insertions(+) diff --git a/docs/source/deployment/docker.rst b/docs/source/deployment/docker.rst index c9653aa0f039..0c7dd17e9363 100644 --- a/docs/source/deployment/docker.rst +++ b/docs/source/deployment/docker.rst @@ -324,6 +324,21 @@ To pull the minimal Isaac Lab container, run: docker pull nvcr.io/nvidia/isaac-lab:3.0.0-beta1 +.. attention:: + + If the pre-built image you use runs as a **non-root** user (uid/gid 1000) -- as Isaac Lab + 3.0.0-beta2 and later do -- the bind-mounted host directories below must be writable by that + user. Docker creates any missing bind-mount source directory as ``root``, which the non-root + runtime user cannot write to, leading to startup errors such as + ``PermissionError: [Errno 13] Permission denied: '/root/.local/share/ov/data/exts'``. + Pre-create the host directories and make them writable by uid/gid 1000 before running the + container: + + .. code:: bash + + mkdir -p ~/docker/isaac-sim/{cache/kit,cache/ov,cache/pip,cache/glcache,cache/computecache,logs,data,documents} + sudo chown -R 1000:1000 ~/docker/isaac-sim + To run the Isaac Lab container with an interactive bash session, run: .. code:: bash diff --git a/docs/source/how-to/cloudxr_teleoperation.rst b/docs/source/how-to/cloudxr_teleoperation.rst index d85b0e885bc9..3c73fb8f36a7 100644 --- a/docs/source/how-to/cloudxr_teleoperation.rst +++ b/docs/source/how-to/cloudxr_teleoperation.rst @@ -448,6 +448,41 @@ components run inside one container with Isaac Lab in this release. The CloudXR runtime auto-launches when a teleop script is started, so no separate runtime command is needed. +.. attention:: + + Recent Isaac Lab Docker images (3.0.0-beta2 and later) run as a **non-root** user + (uid/gid 1000). Persistent named volumes or host directories that were created by an + earlier root-based image are owned by ``root`` and are **not writable** by the runtime + user. The XR teleop workflow trips on this first, because it writes the extension + registry cache under the runtime home. The failure looks like:: + + [Error] [carb.scripting-python.plugin] PermissionError: [Errno 13] Permission denied: '/root/.local/share/ov/data/exts' + + followed by a cascade of extension-registry errors that abort the app *before* the XR + session can start:: + + [Error] [omni.ext.plugin] Syncing with extension registry unavailable. + [Error] [omni.ext.plugin] Failed to resolve extension dependencies. Failure hints: + * No versions of omni.kit.xr.bundle.generic that satisfies: isaaclab.python.xr.openxr-3.0.0 ... + [Error] [omni.kit.app.plugin] Exiting app because of dependency solver failure... + + The XR bundle is not actually missing -- the registry never synced because its cache + directory could not be created. To fix it, make the persistent storage writable by + uid/gid 1000 before relaunching: + + * **Docker Compose:** recreate the named volumes, e.g. + + .. code-block:: bash + + docker compose --file docker-compose.yaml --profile base --env-file .env.base down --volumes + + See :ref:`deployment-docker` for details. To preserve cached data instead of + deleting it, ``chown`` the volume: ``docker run --rm -v docker_isaac-data:/data alpine + chown -R 1000:1000 /data``. + * **Single container with bind mounts:** pre-create the host directories and + ``sudo chown -R 1000:1000`` them before launching, so the non-root user can write to + them. + Run the teleop script (e.g. ``record_demos.py`` to record demonstrations): .. code-block:: bash From ea1f61a5dd211a2ec1aa44d49f5ceab096c201c7 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Tue, 9 Jun 2026 12:09:15 +0100 Subject: [PATCH 34/40] Install ovphysx wheel by default in `--install` (#5780) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Promote the publicly available `ovphysx` PyPI wheel out of the manual `ov[ovphysx]` extra and into the default `./isaaclab.sh --install` flow, mirroring how the newton wheel is treated. The OVRTX renderer wheel stays opt-in via `--install 'ov[ovrtx]'` or `--install 'ov[all]'`. Concretely: - `MANUAL_EXTRA_FEATURES` drops `"ov"` (it now only contains `"contrib"`), so the `ov` feature is part of the automatic `-i` / `-i all` set alongside `newton`, `rl`, and `visualizer`. - `_install_ov_extra_dependencies("")` no longer prints a help message and returns; it now installs `isaaclab_ovphysx[ovphysx]`. Explicit `ov[ovrtx]`, `ov[ovphysx]`, and `ov[all]` behavior is unchanged. - CLI `--install` help text and the `command_install` docstring are updated to reflect the new default. - With the wheel guaranteed in every standard install, the `pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed")` guards (9 sites) and one inner `importorskip("isaaclab_ovphysx.tensor_types")` call are removed from the `isaaclab_ovphysx` test suite. The `isaaclab_ov` CI job (whose `filter-pattern: "isaaclab_ov"` already collects these tests) now exercises them for real instead of silently skipping. No new required dependency is added; `source/isaaclab_ovphysx/setup.py` already declared `EXTRAS_REQUIRE = {"ovphysx": ["ovphysx"]}`. The extra remains unpinned for now — pinning a minimum version is a sensible follow-up once we lock in a release. Fixes # (n/a) ## Type of change - New feature (non-breaking change which adds functionality) Strictly, the default install footprint grows by one PyPI wheel and previously-skipped tests now run, so downstream consumers of `--install` see new behavior — but no public API is removed or renamed and all existing `ov[...]` selectors continue to work as before. ## Screenshots N/A — install-CLI and test-gating change. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation (CLI `--help` text and `command_install` docstring updated) - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works (new `test_all_installs_ov_with_default_ovphysx_selector` plus updates to `test_manual_extra_features` and `test_all_does_not_install_manual_extra_dependencies`; 51/51 pass in `test_install_command_parsing.py`) - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package — `source/isaaclab/changelog.d/antoiner-ovphysx-default-install.rst` and `source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-default-install.rst` - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .github/workflows/build.yaml | 1 + pyproject.toml | 1 + .../antoiner-ovphysx-device-split-ci.rst | 12 + .../test/assets/test_articulation.py | 7 +- .../test/assets/test_articulation_helpers.py | 5 +- .../test/assets/test_rigid_object.py | 7 +- .../assets/test_rigid_object_collection.py | 7 +- .../test/assets/test_rigid_object_helpers.py | 5 +- .../test_ovphysx_scene_data_backend.py | 5 +- .../test/sensors/test_contact_sensor.py | 7 +- .../test/sim/test_views_xform_prim_ovphysx.py | 7 +- tools/_device_split.py | 65 +++ tools/conftest.py | 551 +++++++++++------- tools/test_device_split.py | 108 ++++ 14 files changed, 545 insertions(+), 243 deletions(-) create mode 100644 source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-device-split-ci.rst create mode 100644 tools/_device_split.py create mode 100644 tools/test_device_split.py diff --git a/.github/workflows/build.yaml b/.github/workflows/build.yaml index 1c599ebcb988..a121db583ef2 100644 --- a/.github/workflows/build.yaml +++ b/.github/workflows/build.yaml @@ -543,6 +543,7 @@ jobs: isaacsim-base-image: ${{ needs.config.outputs.isaacsim_image_name }} isaacsim-version: ${{ needs.config.outputs.isaacsim_image_tag }} filter-pattern: "isaaclab_ov" + extra-pip-packages: "ovrtx ovphysx" container-name: isaac-lab-ov-test # Folded from the former standalone verify-base-non-root job: reuses the diff --git a/pyproject.toml b/pyproject.toml index 117311ef207c..a64fc84af215 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -196,6 +196,7 @@ ignore-words-list = "haa,slq,collapsable,buss,reacher,thirdparty" markers = [ "isaacsim_ci: mark test to run in isaacsim ci", + "device_split: re-invoke this file once per device (CPU and GPU) in CI due to process-global device locks (e.g., ovphysx<=0.3.7 gap G5)", ] # Add pypi.nvidia.com so that `uv pip install isaaclab[isaacsim]` works without --extra-index-url. diff --git a/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-device-split-ci.rst b/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-device-split-ci.rst new file mode 100644 index 000000000000..7588fd36b241 --- /dev/null +++ b/source/isaaclab_ovphysx/changelog.d/antoiner-ovphysx-device-split-ci.rst @@ -0,0 +1,12 @@ +Fixed +^^^^^ + +* Re-enabled both CPU and GPU coverage in CI for OVPhysX tests by tagging + :file:`test/assets/test_articulation.py`, + :file:`test/assets/test_rigid_object.py`, + :file:`test/assets/test_rigid_object_collection.py`, + :file:`test/sensors/test_contact_sensor.py`, and + :file:`test/sim/test_views_xform_prim_ovphysx.py` with the new + ``device_split`` pytest marker, which causes the CI driver to invoke each + file once per device in separate subprocesses. Works around the + ``ovphysx<=0.3.7`` process-global device lock (gap G5). diff --git a/source/isaaclab_ovphysx/test/assets/test_articulation.py b/source/isaaclab_ovphysx/test/assets/test_articulation.py index 02f382f3f319..a3cc3f0583ed 100644 --- a/source/isaaclab_ovphysx/test/assets/test_articulation.py +++ b/source/isaaclab_ovphysx/test/assets/test_articulation.py @@ -56,9 +56,8 @@ import torch import warp as wp -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx import tensor_types as TT # noqa: E402 @@ -83,6 +82,8 @@ wp.init() +pytestmark = pytest.mark.device_split + _OMNI_PHYSX_SCHEMAS_GAP_REASON = ( "Schema-level fixed-joint creation in :mod:`isaaclab.sim.schemas` imports " diff --git a/source/isaaclab_ovphysx/test/assets/test_articulation_helpers.py b/source/isaaclab_ovphysx/test/assets/test_articulation_helpers.py index db0a2cc89403..da85e53facbc 100644 --- a/source/isaaclab_ovphysx/test/assets/test_articulation_helpers.py +++ b/source/isaaclab_ovphysx/test/assets/test_articulation_helpers.py @@ -19,9 +19,8 @@ from pxr import Sdf, Usd, UsdPhysics -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx.assets.articulation.articulation import Articulation # noqa: E402 diff --git a/source/isaaclab_ovphysx/test/assets/test_rigid_object.py b/source/isaaclab_ovphysx/test/assets/test_rigid_object.py index 7c9567ade19c..046eb7b6e90f 100644 --- a/source/isaaclab_ovphysx/test/assets/test_rigid_object.py +++ b/source/isaaclab_ovphysx/test/assets/test_rigid_object.py @@ -32,9 +32,8 @@ import warp as wp from flaky import flaky -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx.assets import RigidObject # noqa: E402 @@ -56,6 +55,8 @@ wp.init() +pytestmark = pytest.mark.device_split + _logger = logging.getLogger(__name__) diff --git a/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py b/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py index f17b195e8341..c19b2bfb7e92 100644 --- a/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py @@ -28,9 +28,8 @@ import torch import warp as wp -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx.assets import RigidObjectCollection # noqa: E402 @@ -53,6 +52,8 @@ wp.init() +pytestmark = pytest.mark.device_split + _LOCKED_DEVICE: list[str | None] = [None] """Device the session pins to on the first parametrized test that runs.""" diff --git a/source/isaaclab_ovphysx/test/assets/test_rigid_object_helpers.py b/source/isaaclab_ovphysx/test/assets/test_rigid_object_helpers.py index e57d8d2651d7..a8162765a79b 100644 --- a/source/isaaclab_ovphysx/test/assets/test_rigid_object_helpers.py +++ b/source/isaaclab_ovphysx/test/assets/test_rigid_object_helpers.py @@ -15,9 +15,8 @@ import pytest import warp as wp -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx import tensor_types as TT # noqa: E402 diff --git a/source/isaaclab_ovphysx/test/physics/test_ovphysx_scene_data_backend.py b/source/isaaclab_ovphysx/test/physics/test_ovphysx_scene_data_backend.py index 013ef8bdc092..37487b5dd85e 100644 --- a/source/isaaclab_ovphysx/test/physics/test_ovphysx_scene_data_backend.py +++ b/source/isaaclab_ovphysx/test/physics/test_ovphysx_scene_data_backend.py @@ -11,9 +11,8 @@ import pytest -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") diff --git a/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py b/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py index 832929756c2b..a60f7d0424a1 100644 --- a/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py @@ -45,9 +45,8 @@ import warp as wp from flaky import flaky -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx.assets import RigidObject # noqa: E402 @@ -64,6 +63,8 @@ wp.init() +pytestmark = pytest.mark.device_split + # --------------------------------------------------------------------------- # Device-lock autouse fixture # --------------------------------------------------------------------------- diff --git a/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py b/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py index bebd8aaa460d..e606ce7738b9 100644 --- a/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py +++ b/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py @@ -12,9 +12,8 @@ import pytest -# The CI isaaclab_ov* pattern unintentionally collects isaaclab_ovphysx tests, -# but the ovphysx wheel is not installed in that environment. Skip gracefully -# so the isaaclab_ov CI pipeline is not blocked by an unrelated dependency. +# The OVPhysX runtime wheel is optional. Skip gracefully when it is not installed; +# CI jobs that need OVPhysX coverage install it explicitly. pytest.importorskip("ovphysx.types", reason="ovphysx wheel not installed") from isaaclab_ovphysx.physics import OvPhysxCfg # noqa: E402 @@ -25,6 +24,8 @@ OVPHYSX_SIM_CFG = SimulationCfg(physics=OvPhysxCfg()) +pytestmark = pytest.mark.device_split + @pytest.mark.parametrize("device", ["cpu", "cuda:0"]) def test_factory_dispatches_to_ovphysx_frame_view(device): diff --git a/tools/_device_split.py b/tools/_device_split.py new file mode 100644 index 000000000000..e8bad4069133 --- /dev/null +++ b/tools/_device_split.py @@ -0,0 +1,65 @@ +# 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 + +"""Helpers for detecting and driving the ``device_split`` pytest marker. + +Test files that declare ``pytestmark = pytest.mark.device_split`` at module +scope must be re-invoked once per device (CPU and GPU) in separate processes +to work around process-global device locks such as ``ovphysx<=0.3.7`` gap G5. +The :func:`is_device_split_file` predicate lets the per-file CI runner in +``tools/conftest.py`` detect this without importing the test module. +""" + +from __future__ import annotations + +import re +from pathlib import Path + +_DEVICE_SPLIT_MARK_RE = re.compile(r"^\s*pytestmark\b.*\bdevice_split\b", re.MULTILINE) +"""Match a module-level ``pytestmark`` assignment that mentions ``device_split``. + +Recognises both single-mark and single-line list forms: + +* ``pytestmark = pytest.mark.device_split`` +* ``pytestmark = [pytest.mark.device_split, pytest.mark.foo]`` + +Multi-line list forms are not supported (currently no test file uses one); if +a future test needs that, expand the parsing rule. +""" + +# Per-pass pytest ``-k`` selectors used by ``tools/conftest.py`` when a file +# declares the ``device_split`` marker. Each entry is ``(suffix, k_expr)``: +# - ``suffix`` is appended to the JUnit report filename to keep both passes' XML. +# - ``k_expr`` is the ``-k`` keyword expression. ``"cpu or not cuda"`` keeps +# non-parametrized tests in the CPU pass; ``"cuda"`` catches GPU-parametrized +# tests only. +DEVICE_SPLIT_PASSES: list[tuple[str, str]] = [ + ("-cpu", "cpu or not cuda"), + ("-cuda", "cuda"), +] + + +def is_device_split_file(path: Path | str, source: str | None = None) -> bool: + """Return whether the test file at ``path`` declares the ``device_split`` marker. + + Matches :data:`_DEVICE_SPLIT_MARK_RE` against ``source`` when supplied. + Otherwise, reads the file source from ``path``. A missing or unreadable + file returns ``False`` so the caller falls back to the default single-pass + invocation. + + Args: + path: Filesystem path to a candidate test file. + source: Optional preloaded source text to inspect. + + Returns: + ``True`` when the file's module-level ``pytestmark`` mentions + ``device_split``; ``False`` otherwise. + """ + if source is None: + try: + source = Path(path).read_text(encoding="utf-8", errors="replace") + except OSError: + return False + return bool(_DEVICE_SPLIT_MARK_RE.search(source)) diff --git a/tools/conftest.py b/tools/conftest.py index 9187099ee92a..a45f8cd9183c 100644 --- a/tools/conftest.py +++ b/tools/conftest.py @@ -10,6 +10,7 @@ import subprocess import sys import time +from dataclasses import dataclass import pytest from junitparser import Error, JUnitXml, TestCase, TestSuite @@ -17,6 +18,7 @@ # Local imports import test_settings as test_settings # isort: skip +from _device_split import DEVICE_SPLIT_PASSES, is_device_split_file # isort: skip def pytest_ignore_collect(collection_path, config): @@ -400,131 +402,175 @@ def _retry_failed_test_in_fresh_process( ) -def run_individual_tests(test_files, workspace_root, isaacsim_ci): - """Run each test file separately, ensuring one finishes before starting the next.""" - failed_tests = [] - test_status = {} - xml_reports = [] - cold_cache_applied = False +@dataclass +class _PassContext: + """Inputs shared across all pytest invocations for a single test file. - for test_file in test_files: - print(f"\n\n🚀 Running {test_file} independently...\n") - file_name = os.path.basename(test_file) - env = os.environ.copy() - env["PYTHONFAULTHANDLER"] = "1" + Attributes: + test_file: Absolute path to the test file being driven. + file_name: Basename of ``test_file`` (used for JUnit naming). + workspace_root: Repository root; passed to pytest's ``--config-file``. + isaacsim_ci: Whether ``ISAACSIM_CI_SHORT`` is active; toggles the + ``-m isaacsim_ci`` selector. + timeout: Per-pass hard timeout in seconds. + startup_deadline: Per-pass startup-hang deadline in seconds. + env: Environment passed to the pytest subprocess. + """ - timeout = test_settings.PER_TEST_TIMEOUTS.get(file_name, test_settings.DEFAULT_TIMEOUT) + test_file: str + file_name: str + workspace_root: str + isaacsim_ci: bool + timeout: int + startup_deadline: int + env: dict + + +_RESULT_PRIORITY = { + "STARTUP_HANG": 5, + "CRASHED": 4, + "TIMEOUT": 3, + "FAILED": 2, + "passed (shutdown hanged)": 1, + "passed": 0, +} - # Read the test file once for cold-cache check. - try: - with open(test_file) as fh: - test_content = fh.read() - except OSError: - test_content = "" - # The first camera-enabled test in a fresh container compiles shaders - # (~600 s). Give it extra time so that doesn't look like a test timeout. - is_cold_cache_test = not cold_cache_applied and "enable_cameras=True" in test_content - if is_cold_cache_test: - timeout += COLD_CACHE_BUFFER - cold_cache_applied = True - print(f"⏱️ Adding {COLD_CACHE_BUFFER}s cold-cache buffer (timeout now {timeout}s)") +def _merge_pass_status(prev: dict | None, new: dict) -> dict: + """Merge per-pass status dicts into a single per-file entry. - extra = COLD_CACHE_BUFFER if is_cold_cache_test else 0 - startup_deadline = min(timeout, STARTUP_DEADLINE + extra) + Counters (``errors``, ``failures``, ``skipped``, ``tests``, + ``time_elapsed``, ``wall_time``) are summed. ``result`` becomes the more + severe of the two via :data:`_RESULT_PRIORITY`. + """ + if prev is None: + return new + return { + "errors": prev["errors"] + new["errors"], + "failures": prev["failures"] + new["failures"], + "skipped": prev["skipped"] + new["skipped"], + "tests": prev["tests"] + new["tests"], + "time_elapsed": prev["time_elapsed"] + new["time_elapsed"], + "wall_time": prev["wall_time"] + new["wall_time"], + "result": prev["result"] + if _RESULT_PRIORITY.get(prev["result"], 0) >= _RESULT_PRIORITY.get(new["result"], 0) + else new["result"], + } + + +def _run_one_pass( + ctx: _PassContext, + k_expr: str | None, + suffix: str, +) -> tuple[JUnitXml | None, dict, bool]: + """Drive one pytest subprocess for ``ctx.test_file`` and return its results. - cmd = [ - sys.executable, - "-m", - "pytest", - "-s", - "--no-header", - f"--config-file={workspace_root}/pyproject.toml", - f"--junitxml=tests/test-reports-{str(file_name)}.xml", - "--tb=short", - ] - - if isaacsim_ci: - cmd.append("-m") - cmd.append("isaacsim_ci") - - cmd.append(str(test_file)) - - report_file = f"tests/test-reports-{str(file_name)}.xml" - - # -- Run with retry on startup hang or hard timeout ----------------- - returncode, stdout_data, stderr_data, kill_reason = -1, b"", b"", "" - wall_time, pre_kill_diag = 0.0, "" - startup_hang_attempts = 0 - timeout_attempts = 0 - while True: - with contextlib.suppress(FileNotFoundError): - os.remove(report_file) - - returncode, stdout_data, stderr_data, kill_reason, wall_time, pre_kill_diag = ( - capture_test_output_with_timeout( - cmd, timeout, env, startup_deadline=startup_deadline, report_file=report_file - ) - ) + Args: + ctx: Static per-file context (paths, timeouts, env). + k_expr: Optional ``-k`` selector. ``None`` means no selector (default + single-pass invocation). + suffix: Suffix appended to the JUnit report filename, e.g. ``"-cpu"`` + or ``""`` for the unsplit default. - has_report = os.path.exists(report_file) - - if kill_reason == "startup_hang" and startup_hang_attempts < STARTUP_HANG_RETRIES: - startup_hang_attempts += 1 - print( - f"⚠️ {test_file}: startup hang detected after {startup_deadline}s" - f" (attempt {startup_hang_attempts}/{STARTUP_HANG_RETRIES + 1}), retrying..." - ) - if stderr_data: - print("=== STDERR (last 5000 chars) ===") - print(stderr_data.decode("utf-8", errors="replace")[-5000:]) - diag = pre_kill_diag or _capture_system_diagnostics() - if len(diag) > 10000: - diag = diag[:10000] + "\n... (truncated)" - print(diag) - continue + Returns: + A 3-tuple ``(xml_report, status_dict, was_failure)``: + * ``xml_report``: parsed JUnit XML, or ``None`` if the pass produced + no report (e.g. startup hang). + * ``status_dict``: per-pass counters compatible with the entries + currently appended to ``test_status``. + * ``was_failure``: whether the pass should add ``ctx.test_file`` to + the ``failed_tests`` list. + """ + pass_file_label = f"{ctx.file_name}{suffix}" + report_file = f"tests/test-reports-{pass_file_label}.xml" + + cmd = [ + sys.executable, + "-m", + "pytest", + "-s", + "--no-header", + f"--config-file={ctx.workspace_root}/pyproject.toml", + f"--junitxml={report_file}", + "--tb=short", + ] + if ctx.isaacsim_ci: + cmd += ["-m", "isaacsim_ci"] + if k_expr is not None: + cmd += ["-k", k_expr] + cmd.append(str(ctx.test_file)) + + # -- Run with retry on startup hang or hard timeout ----------------- + returncode, stdout_data, stderr_data, kill_reason = -1, b"", b"", "" + wall_time, pre_kill_diag = 0.0, "" + startup_hang_attempts = 0 + timeout_attempts = 0 + while True: + with contextlib.suppress(FileNotFoundError): + os.remove(report_file) - if kill_reason == "timeout" and not has_report and timeout_attempts < TIMEOUT_RETRIES: - timeout_attempts += 1 - print( - f"⚠️ {test_file}: timeout detected after {timeout}s" - f" (attempt {timeout_attempts}/{TIMEOUT_RETRIES + 1}), retrying..." - ) - if stdout_data: - print("=== STDOUT (last 5000 chars) ===") - print(stdout_data.decode("utf-8", errors="replace")[-5000:]) - if stderr_data: - print("=== STDERR (last 5000 chars) ===") - print(stderr_data.decode("utf-8", errors="replace")[-5000:]) - diag = pre_kill_diag or _capture_system_diagnostics() - if len(diag) > 10000: - diag = diag[:10000] + "\n... (truncated)" - print(diag) - continue - break + returncode, stdout_data, stderr_data, kill_reason, wall_time, pre_kill_diag = capture_test_output_with_timeout( + cmd, ctx.timeout, ctx.env, startup_deadline=ctx.startup_deadline, report_file=report_file + ) - # -- Resolve result from kill_reason and report file ---------------- has_report = os.path.exists(report_file) - if kill_reason == "startup_hang": - diag = _get_diagnostics(pre_kill_diag) - print(f"⚠️ {test_file}: startup hang after {STARTUP_HANG_RETRIES + 1} attempt(s)") + if kill_reason == "startup_hang" and startup_hang_attempts < STARTUP_HANG_RETRIES: + startup_hang_attempts += 1 + print( + f"⚠️ {ctx.test_file}{suffix}: startup hang detected after {ctx.startup_deadline}s" + f" (attempt {startup_hang_attempts}/{STARTUP_HANG_RETRIES + 1}), retrying..." + ) + if stderr_data: + print("=== STDERR (last 5000 chars) ===") + print(stderr_data.decode("utf-8", errors="replace")[-5000:]) + diag = pre_kill_diag or _capture_system_diagnostics() + if len(diag) > 10000: + diag = diag[:10000] + "\n... (truncated)" print(diag) + continue - msg = f"Startup hang after {startup_deadline}s (retried {STARTUP_HANG_RETRIES} time(s))" - details = f"{msg}\n\n=== SYSTEM DIAGNOSTICS ===\n{diag}\n\n" - if stderr_data: - details += "=== STDERR (last 5000 chars) ===\n" - details += stderr_data.decode("utf-8", errors="replace")[-5000:] + "\n" + if kill_reason == "timeout" and not has_report and timeout_attempts < TIMEOUT_RETRIES: + timeout_attempts += 1 + print( + f"⚠️ {ctx.test_file}{suffix}: timeout detected after {ctx.timeout}s" + f" (attempt {timeout_attempts}/{TIMEOUT_RETRIES + 1}), retrying..." + ) if stdout_data: - details += "=== STDOUT (last 2000 chars) ===\n" - details += stdout_data.decode("utf-8", errors="replace")[-2000:] + "\n" - - error_report = _create_error_report("startup_hang", file_name, msg, details) - error_report.write(report_file) - xml_reports.append(error_report) - failed_tests.append(test_file) - test_status[test_file] = { + print("=== STDOUT (last 5000 chars) ===") + print(stdout_data.decode("utf-8", errors="replace")[-5000:]) + if stderr_data: + print("=== STDERR (last 5000 chars) ===") + print(stderr_data.decode("utf-8", errors="replace")[-5000:]) + diag = pre_kill_diag or _capture_system_diagnostics() + if len(diag) > 10000: + diag = diag[:10000] + "\n... (truncated)" + print(diag) + continue + break + + # -- Resolve result from kill_reason and report file ---------------- + has_report = os.path.exists(report_file) + + if kill_reason == "startup_hang": + diag = _get_diagnostics(pre_kill_diag) + print(f"⚠️ {ctx.test_file}{suffix}: startup hang after {STARTUP_HANG_RETRIES + 1} attempt(s)") + print(diag) + + msg = f"Startup hang after {ctx.startup_deadline}s (retried {STARTUP_HANG_RETRIES} time(s))" + details = f"{msg}\n\n=== SYSTEM DIAGNOSTICS ===\n{diag}\n\n" + if stderr_data: + details += "=== STDERR (last 5000 chars) ===\n" + details += stderr_data.decode("utf-8", errors="replace")[-5000:] + "\n" + if stdout_data: + details += "=== STDOUT (last 2000 chars) ===\n" + details += stdout_data.decode("utf-8", errors="replace")[-2000:] + "\n" + + error_report = _create_error_report("startup_hang", pass_file_label, msg, details) + error_report.write(report_file) + return ( + error_report, + { "errors": 1, "failures": 0, "skipped": 0, @@ -532,61 +578,63 @@ def run_individual_tests(test_files, workspace_root, isaacsim_ci): "result": "STARTUP_HANG", "time_elapsed": 0.0, "wall_time": wall_time, - } - continue - - if kill_reason == "timeout" and not has_report: - diag = _get_diagnostics(pre_kill_diag) - print(f"Test {test_file} timed out after {timeout} seconds...") - print(diag) + }, + True, + ) - msg = f"Timeout after {timeout} seconds (retried {timeout_attempts} time(s))" - details = f"{msg}\n\n=== SYSTEM DIAGNOSTICS ===\n{diag}\n\n" - if stdout_data: - details += "=== STDOUT (last 5000 chars) ===\n" - details += stdout_data.decode("utf-8", errors="replace")[-5000:] + "\n" - if stderr_data: - details += "=== STDERR (last 5000 chars) ===\n" - details += stderr_data.decode("utf-8", errors="replace")[-5000:] + "\n" - - error_report = _create_error_report("timeout", file_name, msg, details) - error_report.write(report_file) - xml_reports.append(error_report) - failed_tests.append(test_file) - test_status[test_file] = { + if kill_reason == "timeout" and not has_report: + diag = _get_diagnostics(pre_kill_diag) + print(f"Test {ctx.test_file}{suffix} timed out after {ctx.timeout} seconds...") + print(diag) + + msg = f"Timeout after {ctx.timeout} seconds (retried {timeout_attempts} time(s))" + details = f"{msg}\n\n=== SYSTEM DIAGNOSTICS ===\n{diag}\n\n" + if stdout_data: + details += "=== STDOUT (last 5000 chars) ===\n" + details += stdout_data.decode("utf-8", errors="replace")[-5000:] + "\n" + if stderr_data: + details += "=== STDERR (last 5000 chars) ===\n" + details += stderr_data.decode("utf-8", errors="replace")[-5000:] + "\n" + + error_report = _create_error_report("timeout", pass_file_label, msg, details) + error_report.write(report_file) + return ( + error_report, + { "errors": 1, "failures": 0, "skipped": 0, "tests": 1, "result": "TIMEOUT", - "time_elapsed": timeout, + "time_elapsed": ctx.timeout, "wall_time": wall_time, - } - continue - - if not has_report: - reason = ( - _signal_description(-returncode) - if returncode < 0 - else f"Process exited with code {returncode} but produced no report" - ) - diag = _get_diagnostics() - print(f"⚠️ {test_file}: {reason}") - print(diag) + }, + True, + ) - details = f"{reason}\n\n=== SYSTEM DIAGNOSTICS ===\n{diag}\n\n" - if stdout_data: - details += "=== STDOUT (last 2000 chars) ===\n" - details += stdout_data.decode("utf-8", errors="replace")[-2000:] + "\n" - if stderr_data: - details += "=== STDERR (last 2000 chars) ===\n" - details += stderr_data.decode("utf-8", errors="replace")[-2000:] + "\n" - - error_report = _create_error_report("crash", file_name, reason, details) - error_report.write(report_file) - xml_reports.append(error_report) - failed_tests.append(test_file) - test_status[test_file] = { + if not has_report: + reason = ( + _signal_description(-returncode) + if returncode < 0 + else f"Process exited with code {returncode} but produced no report" + ) + diag = _get_diagnostics() + print(f"⚠️ {ctx.test_file}{suffix}: {reason}") + print(diag) + + details = f"{reason}\n\n=== SYSTEM DIAGNOSTICS ===\n{diag}\n\n" + if stdout_data: + details += "=== STDOUT (last 2000 chars) ===\n" + details += stdout_data.decode("utf-8", errors="replace")[-2000:] + "\n" + if stderr_data: + details += "=== STDERR (last 2000 chars) ===\n" + details += stderr_data.decode("utf-8", errors="replace")[-2000:] + "\n" + + error_report = _create_error_report("crash", pass_file_label, reason, details) + error_report.write(report_file) + return ( + error_report, + { "errors": 1, "failures": 0, "skipped": 0, @@ -594,19 +642,21 @@ def run_individual_tests(test_files, workspace_root, isaacsim_ci): "result": "CRASHED", "time_elapsed": 0.0, "wall_time": wall_time, - } - continue + }, + True, + ) - # -- Report file exists: parse actual test results ----------------- - if kill_reason in ("shutdown_hang", "timeout"): - print(f"⚠️ {test_file}: shutdown hanged (killed after {wall_time:.0f}s, test had completed)") + # -- Report file exists: parse actual test results ----------------- + if kill_reason in ("shutdown_hang", "timeout"): + print(f"⚠️ {ctx.test_file}{suffix}: shutdown hanged (killed after {wall_time:.0f}s, test had completed)") - try: - report, errors, failures, skipped, tests, time_elapsed = _read_test_report(report_file, file_name) - except Exception as e: - print(f"Error reading test report {report_file}: {e}") - failed_tests.append(test_file) - test_status[test_file] = { + try: + report, errors, failures, skipped, tests, time_elapsed = _read_test_report(report_file, pass_file_label) + except Exception as e: + print(f"Error reading test report {report_file}: {e}") + return ( + None, + { "errors": 1, "failures": 0, "skipped": 0, @@ -614,60 +664,59 @@ def run_individual_tests(test_files, workspace_root, isaacsim_ci): "result": "FAILED", "time_elapsed": 0.0, "wall_time": wall_time, - } - continue - - has_test_failures = errors > 0 or failures > 0 - ( - report, - errors, - failures, - skipped, - tests, - time_elapsed, - returncode, - stdout_data, - stderr_data, - kill_reason, - wall_time, - pre_kill_diag, - has_test_failures, - ) = _retry_failed_test_in_fresh_process( - test_file=test_file, - file_name=file_name, - cmd=cmd, - timeout=timeout, - env=env, - startup_deadline=startup_deadline, - report_file=report_file, - report=report, - errors=errors, - failures=failures, - skipped=skipped, - tests=tests, - time_elapsed=time_elapsed, - returncode=returncode, - stdout_data=stdout_data, - stderr_data=stderr_data, - kill_reason=kill_reason, - wall_time=wall_time, - pre_kill_diag=pre_kill_diag, + }, + True, ) - xml_reports.append(report) - shutdown_hanged = kill_reason in ("shutdown_hang", "timeout") and not has_test_failures + ( + report, + errors, + failures, + skipped, + tests, + time_elapsed, + returncode, + stdout_data, + stderr_data, + kill_reason, + wall_time, + pre_kill_diag, + has_test_failures, + ) = _retry_failed_test_in_fresh_process( + test_file=ctx.test_file, + file_name=ctx.file_name, + cmd=cmd, + timeout=ctx.timeout, + env=ctx.env, + startup_deadline=ctx.startup_deadline, + report_file=report_file, + report=report, + errors=errors, + failures=failures, + skipped=skipped, + tests=tests, + time_elapsed=time_elapsed, + returncode=returncode, + stdout_data=stdout_data, + stderr_data=stderr_data, + kill_reason=kill_reason, + wall_time=wall_time, + pre_kill_diag=pre_kill_diag, + ) - if has_test_failures or (returncode != 0 and not shutdown_hanged): - failed_tests.append(test_file) + shutdown_hanged = kill_reason in ("shutdown_hang", "timeout") and not has_test_failures + was_failure = has_test_failures or (returncode != 0 and not shutdown_hanged) - if shutdown_hanged: - result = "passed (shutdown hanged)" - elif has_test_failures: - result = "FAILED" - else: - result = "passed" + if shutdown_hanged: + result = "passed (shutdown hanged)" + elif has_test_failures: + result = "FAILED" + else: + result = "passed" - test_status[test_file] = { + return ( + report, + { "errors": errors, "failures": failures, "skipped": skipped, @@ -675,7 +724,71 @@ def run_individual_tests(test_files, workspace_root, isaacsim_ci): "result": result, "time_elapsed": time_elapsed, "wall_time": wall_time, - } + }, + was_failure, + ) + + +def run_individual_tests(test_files, workspace_root, isaacsim_ci): + """Run each test file separately, ensuring one finishes before starting the next.""" + failed_tests = [] + test_status = {} + xml_reports = [] + cold_cache_applied = False + + for test_file in test_files: + print(f"\n\n🚀 Running {test_file} independently...\n") + file_name = os.path.basename(test_file) + env = os.environ.copy() + env["PYTHONFAULTHANDLER"] = "1" + + timeout = test_settings.PER_TEST_TIMEOUTS.get(file_name, test_settings.DEFAULT_TIMEOUT) + + # Read the test file once for cold-cache and device-split detection. + try: + with open(test_file) as fh: + test_content = fh.read() + except OSError: + test_content = "" + + # The first camera-enabled test in a fresh container compiles shaders + # (~600 s). Give it extra time so that doesn't look like a test timeout. + is_cold_cache_test = not cold_cache_applied and "enable_cameras=True" in test_content + if is_cold_cache_test: + timeout += COLD_CACHE_BUFFER + cold_cache_applied = True + print(f"⏱️ Adding {COLD_CACHE_BUFFER}s cold-cache buffer (timeout now {timeout}s)") + + extra = COLD_CACHE_BUFFER if is_cold_cache_test else 0 + startup_deadline = min(timeout, STARTUP_DEADLINE + extra) + + ctx = _PassContext( + test_file=test_file, + file_name=file_name, + workspace_root=workspace_root, + isaacsim_ci=isaacsim_ci, + timeout=timeout, + startup_deadline=startup_deadline, + env=env, + ) + + if is_device_split_file(test_file, source=test_content): + print(f"⚙️ device_split detected — invoking {file_name} once per device (CPU then GPU)") + passes = DEVICE_SPLIT_PASSES + else: + passes = [("", None)] + + merged_status: dict | None = None + for suffix, k_expr in passes: + report, status, was_failure = _run_one_pass(ctx, k_expr=k_expr, suffix=suffix) + if report is not None: + xml_reports.append(report) + if was_failure and test_file not in failed_tests: + failed_tests.append(test_file) + merged_status = _merge_pass_status(merged_status, status) + + assert merged_status is not None # the pass list is never empty + test_status[test_file] = merged_status print("~~~~~~~~~~~~ Finished running all tests") diff --git a/tools/test_device_split.py b/tools/test_device_split.py new file mode 100644 index 000000000000..fb34ce40c4f1 --- /dev/null +++ b/tools/test_device_split.py @@ -0,0 +1,108 @@ +# 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 + +"""Unit tests for ``tools/_device_split.py``.""" + +from __future__ import annotations + +import textwrap +from pathlib import Path + +from _device_split import is_device_split_file + + +def _write(tmp_path: Path, content: str) -> Path: + p = tmp_path / "test_foo.py" + p.write_text(textwrap.dedent(content)) + return p + + +def test_single_mark(tmp_path): + f = _write( + tmp_path, + """ + import pytest + + pytestmark = pytest.mark.device_split + + def test_x(): + pass + """, + ) + assert is_device_split_file(f) is True + + +def test_list_form_single_line(tmp_path): + f = _write( + tmp_path, + """ + import pytest + + pytestmark = [pytest.mark.device_split, pytest.mark.foo] + + def test_x(): + pass + """, + ) + assert is_device_split_file(f) is True + + +def test_preloaded_source(tmp_path): + source = textwrap.dedent( + """ + import pytest + + pytestmark = pytest.mark.device_split + """ + ) + assert is_device_split_file(tmp_path / "does_not_exist.py", source=source) is True + + +def test_no_mark(tmp_path): + f = _write( + tmp_path, + """ + import pytest + + def test_x(): + pass + """, + ) + assert is_device_split_file(f) is False + + +def test_word_in_comment_does_not_match(tmp_path): + f = _write( + tmp_path, + """ + import pytest + + # This file mentions device_split in a comment but is not marked. + + def test_x(): + pass + """, + ) + assert is_device_split_file(f) is False + + +def test_unrelated_pytestmark_does_not_match(tmp_path): + f = _write( + tmp_path, + """ + import pytest + + pytestmark = pytest.mark.skipif(False, reason="x") + + def test_x(): + pass + """, + ) + assert is_device_split_file(f) is False + + +def test_missing_file(tmp_path): + # A path that does not exist must not raise; treat as not-marked. + assert is_device_split_file(tmp_path / "does_not_exist.py") is False From 5124aa17e227568307a2f14107fc8536de7aa2fa Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Tue, 9 Jun 2026 13:52:23 +0100 Subject: [PATCH 35/40] Fix sensor ancestor suffix trimming (#6068) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description Fixes rigid-body ancestor expression resolution for sensors mounted under a non-rigid child when the terminal child suffix also appears earlier in the path. The old implementation used an unbounded ``str.replace()``, which could remove more than the sensor-relative suffix. Simple example: ```text target_expr = /World/envs/env_.*/Robot/link/link relative_path = link old result = /World/envs/env_.*/Robot new result = /World/envs/env_.*/Robot/link ``` The fix verifies that the relative path is a terminal suffix and slices only that end segment. No issue filed. Validation: - `./isaaclab.sh -p -m pytest source/isaaclab/test/sensors/test_sensor_base.py::test_rigid_body_ancestor_expr_trims_only_terminal_suffix -q` - `PATH=/tmp/git-lfs-v3.7.1:$PATH ./isaaclab.sh -f` ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots Not applicable. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation, or documentation is not required for this change - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --- .../fix-sensor-base-ancestor-suffix.rst | 5 ++++ .../isaaclab/isaaclab/sensors/sensor_base.py | 8 ++++++- .../isaaclab/test/sensors/test_sensor_base.py | 24 +++++++++++++++++++ 3 files changed, 36 insertions(+), 1 deletion(-) create mode 100644 source/isaaclab/changelog.d/fix-sensor-base-ancestor-suffix.rst diff --git a/source/isaaclab/changelog.d/fix-sensor-base-ancestor-suffix.rst b/source/isaaclab/changelog.d/fix-sensor-base-ancestor-suffix.rst new file mode 100644 index 000000000000..26ec4a98f416 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-sensor-base-ancestor-suffix.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed rigid-body ancestor resolution for sensor paths whose terminal child path + is repeated earlier in the prim path. diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index a72ed6b9efaa..c84bd50c7ac6 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -472,6 +472,12 @@ def _resolve_rigid_body_ancestor_expr( return target_expr, None, None relative_path = prim.GetPath().MakeRelativePath(ancestor_prim.GetPath()).pathString - rigid_parent_expr = target_expr.replace("/" + relative_path, "") + suffix = "/" + relative_path + if not target_expr.endswith(suffix): + raise RuntimeError( + f"Failed to build rigid body ancestor expression: target expression {target_expr!r} does not end " + f"with relative path {relative_path!r}." + ) + rigid_parent_expr = target_expr[: -len(suffix)] fixed_pos_b, fixed_quat_b = resolve_prim_pose(prim, ancestor_prim) return rigid_parent_expr, fixed_pos_b, fixed_quat_b diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 3d8d6af9090c..ddf3d1f9d9f6 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -21,6 +21,8 @@ import torch import warp as wp +from pxr import UsdPhysics + import isaaclab.sim as sim_utils from isaaclab.sensors import SensorBase, SensorBaseCfg from isaaclab.utils.configclass import configclass @@ -228,3 +230,25 @@ def test_sensor_reset(create_dummy_sensor, device): sensor.data.count[cont_ids], torch.tensor(k + 6, device=device, dtype=torch.int32).repeat(len(cont_ids)), ) + + +@pytest.mark.parametrize("device", ("cpu",)) +def test_rigid_body_ancestor_expr_trims_only_terminal_suffix(create_dummy_sensor, device): + """Test that ancestor expression trimming keeps repeated path segments above the sensor.""" + sensor_cfg, _, _ = create_dummy_sensor + + parent_path = "/World/envs/env_00/Robot/link" + child_path = parent_path + "/link" + sim_utils.create_prim(parent_path, "Xform") + sim_utils.create_prim(child_path, "Xform") + UsdPhysics.RigidBodyAPI.Apply(sim_utils.get_current_stage().GetPrimAtPath(parent_path)) + sim_utils.update_stage() + + sensor_cfg.prim_path = "/World/envs/env_.*/Robot/link/link" + sensor = DummySensor(cfg=sensor_cfg) + + rigid_parent_expr, fixed_pos_b, fixed_quat_b = sensor._resolve_rigid_body_ancestor_expr() + + assert rigid_parent_expr == "/World/envs/env_.*/Robot/link" + assert fixed_pos_b is not None + assert fixed_quat_b is not None From 5189e4753df82960cb6028018516d6fc32721751 Mon Sep 17 00:00:00 2001 From: hujc Date: Tue, 9 Jun 2026 08:20:57 -0700 Subject: [PATCH 36/40] [MGPU] Sim: honor device kwarg over sim_cfg.device in build_simulation_context (#5881) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ## Summary - `build_simulation_context(device="cuda:N", sim_cfg=...)` silently dropped the explicit `device` kwarg when a `sim_cfg` was passed, falling back to `sim_cfg.device` (default `cuda:0`). - The multi-GPU CI lane sets `ISAACLAB_SIM_DEVICE=cuda:N` per shard, so tests that pass `device="cuda:N"` got `cuda:0` instead. Downstream Warp kernels then ran on `cuda:0` while the rest of the test believed it was on `cuda:N`: ``` RuntimeError: Error launching kernel 'set_root_link_pose_to_sim_index', trying to launch on device='cuda:0', but input array for argument 'env_ids' is on device=cuda:2. ``` - Fix: make `device`'s default `None` (sentinel) and apply it as an override after `sim_cfg` is resolved, so an explicit kwarg wins whether or not a `sim_cfg` was supplied. ## 1. The bug ```python def build_simulation_context(..., device: str = "cuda:0", sim_cfg=None, ...): if sim_cfg is None: sim_cfg = SimulationCfg(device=device, ...) # ^^ explicit `device` only used in the no-sim_cfg path; otherwise ignored ``` When a caller passed both `sim_cfg=` and `device="cuda:2"`, the kwarg was thrown away. Code that pulled the active device from `sim_cfg.device` saw `cuda:0`; Warp arrays allocated against the cfg device landed on `cuda:0` while torch ops driven by the kwarg ran on `cuda:2` — the cross-device kernel-launch error above. ## 2. Fix ```python def build_simulation_context(..., device: str | None = None, sim_cfg=None, ...): if sim_cfg is None: gravity = (0.0, 0.0, -9.81) if gravity_enabled else (0.0, 0.0, 0.0) sim_cfg = SimulationCfg(dt=dt, gravity=gravity) if device is not None: sim_cfg.device = device # explicit kwarg wins in both branches ``` `device=None` (default) means "use whatever the cfg already has". `device="cuda:N"` is honored even when a cfg is also passed. ## 3. Validation `source/isaaclab/test/sim/test_build_simulation_context_{headless,nonheadless}.py::test_build_simulation_context_cfg` is updated to assert the new override semantics (explicit `device` wins over `sim_cfg.device`). On local multi-GPU/MIG hardware, `build_simulation_context(sim_cfg=cfg, device="cuda:N")` previously hit the kernel-launch assertion; with the fix it runs on the requested device. Consumed by the multi-GPU CI lane (#5823). --- .../jichuanh-fix-build-sim-context-device.rst | 11 ++++++++++ .../isaaclab/sim/simulation_context.py | 20 ++++++++++++++++--- .../test_build_simulation_context_headless.py | 19 +++++++++++++++--- ...st_build_simulation_context_nonheadless.py | 20 +++++++++++++++---- 4 files changed, 60 insertions(+), 10 deletions(-) create mode 100644 source/isaaclab/changelog.d/jichuanh-fix-build-sim-context-device.rst diff --git a/source/isaaclab/changelog.d/jichuanh-fix-build-sim-context-device.rst b/source/isaaclab/changelog.d/jichuanh-fix-build-sim-context-device.rst new file mode 100644 index 000000000000..89e774bd26d7 --- /dev/null +++ b/source/isaaclab/changelog.d/jichuanh-fix-build-sim-context-device.rst @@ -0,0 +1,11 @@ +Fixed +^^^^^ + +* Fixed :func:`isaaclab.sim.build_simulation_context` silently ignoring the + ``device`` kwarg when ``sim_cfg`` is also provided. Most test callers pass + both kwargs together; the helper now applies the explicit ``device`` over + ``sim_cfg.device`` so the caller's choice wins. Without this, warp kernel + launches in :mod:`isaaclab_newton.assets.articulation` raised device + mismatch errors on non-default GPUs (``env_ids`` allocated on the test's + device while the articulation's resolved device came from the untouched + ``sim_cfg`` default ``cuda:0``). diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 334272636871..2f587d745bd2 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -962,7 +962,7 @@ def _predicate(prim: Usd.Prim) -> bool: def build_simulation_context( create_new_stage: bool = True, gravity_enabled: bool = True, - device: str = "cuda:0", + device: str | None = None, dt: float = 0.01, sim_cfg: SimulationCfg | None = None, add_ground_plane: bool = False, @@ -975,7 +975,11 @@ def build_simulation_context( Args: create_new_stage: Whether to create a new stage. Defaults to True. gravity_enabled: Whether to enable gravity. Defaults to True. - device: Device to run the simulation on. Defaults to "cuda:0". + device: Device to run the simulation on. When given alongside ``sim_cfg``, + overrides ``sim_cfg.device`` so the caller's explicit choice wins + (most test callers pass both, expecting this behavior). Defaults to + ``None``, meaning ``sim_cfg.device`` is left untouched and a freshly + built ``sim_cfg`` uses :class:`SimulationCfg`'s default device. dt: Time step for the simulation. Defaults to 0.01. sim_cfg: SimulationCfg to use. Defaults to None. add_ground_plane: Whether to add a ground plane. Defaults to False. @@ -997,7 +1001,17 @@ def build_simulation_context( if sim_cfg is None: gravity = (0.0, 0.0, -9.81) if gravity_enabled else (0.0, 0.0, 0.0) - sim_cfg = SimulationCfg(device=device, dt=dt, gravity=gravity) + sim_cfg = SimulationCfg(dt=dt, gravity=gravity) + if device is not None: + # Honor the explicit device kwarg in both branches: when sim_cfg is + # freshly built, this picks the device; when sim_cfg is passed in, + # this overrides its (possibly default) device. Without the override, + # callers passing both ``sim_cfg=`` and + # ``device=cuda:N`` silently got sim_cfg's device, causing warp + # kernel-launch mismatches when test fixtures allocated tensors on + # the requested device while assets resolved their device from the + # untouched sim_cfg. + sim_cfg.device = device sim = SimulationContext(sim_cfg) diff --git a/source/isaaclab/test/sim/test_build_simulation_context_headless.py b/source/isaaclab/test/sim/test_build_simulation_context_headless.py index 8f13d79041e7..4ceae87b9878 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.py @@ -75,7 +75,14 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light @pytest.mark.isaacsim_ci def test_build_simulation_context_cfg(): - """Test that the simulation context is built with the correct cfg and values don't get overridden.""" + """Test that the simulation context honors sim_cfg's values, with an explicit + device override winning when both ``sim_cfg`` and ``device`` are passed. + + Most test callers pass both kwargs together expecting the device kwarg to + win; the override branch in :func:`build_simulation_context` exists for + that case. ``gravity`` and ``dt`` are not overridable by the helper's + kwargs (only sim_cfg's values are used). + """ dt = 0.001 # Non-standard gravity gravity = (0.0, 0.0, -1.81) @@ -87,8 +94,14 @@ def test_build_simulation_context_cfg(): dt=dt, ) - with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: - # Values from sim_cfg should not be overridden by build_simulation_context args + # Pass only sim_cfg: gravity, device, dt all come from sim_cfg (kwargs ignored). + with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01) as sim: assert sim.cfg.gravity == gravity assert sim.cfg.device == device assert sim.cfg.dt == dt + + # Pass sim_cfg and an explicit device override: device kwarg wins. + with build_simulation_context(sim_cfg=cfg, device="cpu") as sim: + assert sim.cfg.gravity == gravity + assert sim.cfg.device == "cpu" + assert sim.cfg.dt == dt diff --git a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py index 8c053bc51cda..09bfe3091839 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -70,8 +70,14 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light def test_build_simulation_context_cfg(): - """Test that the simulation context is built with the correct cfg and values don't get overridden.""" - + """Test that the simulation context honors sim_cfg's values, with an explicit + device override winning when both ``sim_cfg`` and ``device`` are passed. + + Most test callers pass both kwargs together expecting the device kwarg to + win; the override branch in :func:`build_simulation_context` exists for + that case. ``gravity`` and ``dt`` are not overridable by the helper's + kwargs (only sim_cfg's values are used). + """ dt = 0.001 # Non-standard gravity gravity = (0.0, 0.0, -1.81) @@ -83,8 +89,14 @@ def test_build_simulation_context_cfg(): dt=dt, ) - with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: - # Values from sim_cfg should not be overridden by build_simulation_context args + # Pass only sim_cfg: gravity, device, dt all come from sim_cfg (kwargs ignored). + with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01) as sim: assert sim.cfg.gravity == gravity assert sim.cfg.device == device assert sim.cfg.dt == dt + + # Pass sim_cfg and an explicit device override: device kwarg wins. + with build_simulation_context(sim_cfg=cfg, device="cpu") as sim: + assert sim.cfg.gravity == gravity + assert sim.cfg.device == "cpu" + assert sim.cfg.dt == dt From d720975cc99524e3f8db6d6a4036e2af2f5c733a Mon Sep 17 00:00:00 2001 From: Maximilian Krause <99733341+maxkra15@users.noreply.github.com> Date: Tue, 9 Jun 2026 09:05:57 -0700 Subject: [PATCH 37/40] Expose Newton visualizer particle options (#6042) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description This PR adds particle visualization controls to `NewtonVisualizerCfg`. It exposes: - `show_particles` to enable Newton particle rendering through config. - `particle_color` to optionally override the Newton viewer particle color for `/model/particles`. Motivation: MPM and particle-based demos currently need to reach into the private Newton viewer instance to show particles or customize particle appearance. This keeps that behavior on the public visualizer config surface and preserves Newton’s default behavior when `particle_color=None`. Fixes # N/A ## Type of change - New feature (non-breaking change which adds functionality) ## Screenshots Not applicable. ## Checklist - [x] I have added tests that prove my feature works - [x] I have run the `pre-commit` checks with `./isaaclab.sh --format` --- .../max-newton-visualizer-particles.rst | 5 ++ .../newton/newton_visualizer.py | 42 ++++++++++++++ .../newton/newton_visualizer_cfg.py | 9 +++ .../test/test_newton_adapter.py | 56 +++++++++++++++++++ 4 files changed, 112 insertions(+) create mode 100644 source/isaaclab_visualizers/changelog.d/max-newton-visualizer-particles.rst diff --git a/source/isaaclab_visualizers/changelog.d/max-newton-visualizer-particles.rst b/source/isaaclab_visualizers/changelog.d/max-newton-visualizer-particles.rst new file mode 100644 index 000000000000..7ddb1d83ef5a --- /dev/null +++ b/source/isaaclab_visualizers/changelog.d/max-newton-visualizer-particles.rst @@ -0,0 +1,5 @@ +Added +^^^^^ + +* Added Newton visualizer configuration options for showing particles and + setting their color. diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py index 7a8ecfc2bb2b..83212dcd5add 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer.py @@ -76,6 +76,10 @@ def __init__( self._fallback_draw_controls = False self._update_frequency = update_frequency self._color_edit3_prefers_sequence: bool | None = None + self.particle_color: tuple[float, float, float] | None = None + self._particle_color_buffer: wp.array | None = None + self._particle_color_buffer_count = 0 + self._particle_color_buffer_value: tuple[float, float, float] | None = None try: self.register_ui_callback(self._render_training_controls, position="side") @@ -148,6 +152,37 @@ def _coerce_color3(self, color) -> tuple[float, float, float]: return (float(color.x), float(color.y), float(color.z)) return (float(color[0]), float(color[1]), float(color[2])) + def _particle_color_array(self, count: int) -> wp.array: + """Return a cached Warp color array for Newton's particle point batch.""" + color = self._coerce_color3(self.particle_color) + if ( + self._particle_color_buffer is None + or self._particle_color_buffer_count != count + or self._particle_color_buffer_value != color + ): + self._particle_color_buffer = wp.full( + shape=count, + value=wp.vec3(*color), + dtype=wp.vec3, + device=self.device, + ) + self._particle_color_buffer_count = count + self._particle_color_buffer_value = color + return self._particle_color_buffer + + def log_points(self, name, points, radii=None, colors=None, hidden=False): + """Apply configured model-particle appearance while preserving Newton's point logging. + + The configured particle color only applies to Newton's canonical + ``/model/particles`` point batch. User-defined point clouds retain the + colors provided by their own ``log_points`` calls. + """ + if name != "/model/particles" or points is None or self.particle_color is None: + return super().log_points(name, points, radii, colors, hidden) + + colors = self._particle_color_array(len(points)) + return super().log_points(name, points, radii, colors, hidden) + def _color_edit3_compat(self, imgui, label: str, color): """ # Handle imgui.color_edit3 API differences between bindings. @@ -229,6 +264,9 @@ def _render_left_panel(self): show_com = self.show_com changed, self.show_com = imgui.checkbox("Show Center of Mass", show_com) + show_particles = self.show_particles + changed, self.show_particles = imgui.checkbox("Show Particles", show_particles) + imgui.set_next_item_open(True, imgui.Cond_.appearing) if imgui.collapsing_header("Rendering Options"): imgui.separator() @@ -430,6 +468,8 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: self._viewer.show_springs = self.cfg.show_springs self._viewer.show_inertia_boxes = self.cfg.show_inertia_boxes self._viewer.show_com = self.cfg.show_com + self._viewer.show_particles = self.cfg.show_particles + self._viewer.particle_color = self.cfg.particle_color self._viewer.renderer.draw_shadows = self.cfg.enable_shadows self._viewer.renderer.draw_sky = self.cfg.enable_sky @@ -459,6 +499,8 @@ def initialize(self, scene_data_provider: SceneDataProvider) -> None: ("tiled_cam_num", self.cfg.tiled_cam_num), ("num_visualized_envs", num_visualized_envs), ("headless", self.cfg.headless), + ("show_particles", self.cfg.show_particles), + ("particle_color", self.cfg.particle_color), ], ) self._is_initialized = True diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer_cfg.py b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer_cfg.py index e52bb273c140..67336c054d53 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer_cfg.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/newton/newton_visualizer_cfg.py @@ -46,6 +46,15 @@ class NewtonVisualizerCfg(VisualizerCfg): show_com: bool = False """Show center of mass visualization.""" + show_particles: bool = False + """Show particle visualization.""" + + particle_color: tuple[float, float, float] | None = None + """Optional particle color RGB [0, 1]. If None, use Newton viewer defaults. + + Values are passed through to the Newton viewer unchanged. + """ + enable_shadows: bool = True """Enable shadow rendering.""" diff --git a/source/isaaclab_visualizers/test/test_newton_adapter.py b/source/isaaclab_visualizers/test/test_newton_adapter.py index 50d76902d3f0..8ba14478bdda 100644 --- a/source/isaaclab_visualizers/test/test_newton_adapter.py +++ b/source/isaaclab_visualizers/test/test_newton_adapter.py @@ -9,8 +9,11 @@ from types import SimpleNamespace +import numpy as np import torch +import warp as wp from isaaclab_visualizers.newton import NewtonVisualizer, NewtonVisualizerCfg +from isaaclab_visualizers.newton.newton_visualizer import NewtonViewerGL from isaaclab_visualizers.newton_adapter import ( VISUALIZER_INFINITE_PLANE_SIZE, apply_viewer_visible_worlds, @@ -101,6 +104,59 @@ def set_visible_worlds(self, worlds): assert calls[-1] is None +def test_newton_visualizer_cfg_exposes_particle_options(): + cfg = NewtonVisualizerCfg(show_particles=True, particle_color=(0.1, 0.2, 0.3)) + + assert cfg.show_particles is True + assert cfg.particle_color == (0.1, 0.2, 0.3) + + +def test_newton_viewer_particle_color_override(monkeypatch): + from newton.viewer import ViewerGL + + viewer = NewtonViewerGL.__new__(NewtonViewerGL) + viewer.device = "cpu" + viewer.particle_color = (0.1, 0.2, 0.3) + viewer._particle_color_buffer = None + viewer._particle_color_buffer_count = 0 + viewer._particle_color_buffer_value = None + points = wp.zeros(4, dtype=wp.vec3, device="cpu") + calls = [] + + def _log_points(self, name, points, radii=None, colors=None, hidden=False): + calls.append((name, points, radii, colors, hidden)) + + monkeypatch.setattr(ViewerGL, "log_points", _log_points) + + viewer.log_points("/model/particles", points, colors=None) + + name, _, _, colors, hidden = calls[-1] + assert name == "/model/particles" + assert hidden is False + assert isinstance(colors, wp.array) + assert colors.shape[0] == 4 + np.testing.assert_allclose(colors.numpy()[0], np.array([0.1, 0.2, 0.3], dtype=np.float32), rtol=1.0e-6) + + +def test_newton_viewer_particle_color_override_leaves_other_points_unchanged(monkeypatch): + from newton.viewer import ViewerGL + + viewer = NewtonViewerGL.__new__(NewtonViewerGL) + viewer.particle_color = (0.1, 0.2, 0.3) + points = wp.zeros(1, dtype=wp.vec3, device="cpu") + original_colors = object() + calls = [] + + def _log_points(self, name, points, radii=None, colors=None, hidden=False): + calls.append((name, colors)) + + monkeypatch.setattr(ViewerGL, "log_points", _log_points) + + viewer.log_points("/debug/points", points, colors=original_colors) + + assert calls[-1] == ("/debug/points", original_colors) + + class _BodyQ: shape = (1,) From 166f3148388373da975fd595a864cdb4b7ab6dd1 Mon Sep 17 00:00:00 2001 From: Antoine RICHARD Date: Tue, 9 Jun 2026 17:06:11 +0100 Subject: [PATCH 38/40] Fix kitless OVPhysX scene cloning (#6072) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit # Description OVPhysX can run kitless in a state where Carbonite exposes the Fabric USD notice interface but the Python `usdrt` module is not importable. In that state, `disabled_fabric_change_notifies()` should fall back to its intended no-op behavior instead of failing during scene cloning. This PR keeps Fabric notice suspension active when `usdrt` is available, but treats only a missing top-level `usdrt` module as unavailable Fabric notice suspension. It also removes redundant `queue_usd_replication(...)` calls from the OVPhysX `RigidObject`, `Articulation`, and `RigidObjectCollection` constructors. OVPhysX assets continue to enqueue `queue_ovphysx_replication(...)` for backend runtime cloning. Fixes # ## Type of change - Bug fix (non-breaking change which fixes an issue) ## Screenshots Not applicable. ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh -f` - [x] I have made corresponding changes to the documentation, or no documentation update is required - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have added a changelog fragment under `source//changelog.d/` for every touched package (do **not** edit `CHANGELOG.rst` or bump `extension.toml` — CI handles that) - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there ## Testing - `./isaaclab.sh -p -m pytest -q source/isaaclab/test/sim/test_cloner.py::test_disabled_fabric_change_notifies_noops_when_usdrt_unavailable` (`1 passed`) - `./isaaclab.sh -p -m pytest -q source/isaaclab_physx/test/sim/test_cloner.py::test_disabled_fabric_change_notifies_toggles_ifabricusd_flag` (`2 passed`) - `./isaaclab.sh -p -m pytest -q source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py::test_world_pose_equals_parent_plus_offset -k cpu` (`1 passed, 1 deselected`) - `./isaaclab.sh -p -m pytest -q source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py::test_world_pose_equals_parent_plus_offset -k cuda` (`1 passed, 1 deselected`) - `PATH=/tmp/git-lfs-v3.7.1:$PATH ./isaaclab.sh -f` --- .../fix-kitless-fabric-notices.rst | 5 ++++ .../isaaclab/cloner/_fabric_notices.py | 8 +++++- source/isaaclab/test/sim/test_cloner.py | 27 ++++++++++++++++++- .../changelog.d/skip-usd-replication.rst | 5 ++++ .../assets/articulation/articulation.py | 2 -- .../assets/rigid_object/rigid_object.py | 2 -- .../rigid_object_collection.py | 2 -- 7 files changed, 43 insertions(+), 8 deletions(-) create mode 100644 source/isaaclab/changelog.d/fix-kitless-fabric-notices.rst create mode 100644 source/isaaclab_ovphysx/changelog.d/skip-usd-replication.rst diff --git a/source/isaaclab/changelog.d/fix-kitless-fabric-notices.rst b/source/isaaclab/changelog.d/fix-kitless-fabric-notices.rst new file mode 100644 index 000000000000..7fa10ac24367 --- /dev/null +++ b/source/isaaclab/changelog.d/fix-kitless-fabric-notices.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Fixed :func:`~isaaclab.cloner.disabled_fabric_change_notifies` to no-op + when ``usdrt`` is unavailable in kitless runtimes. diff --git a/source/isaaclab/isaaclab/cloner/_fabric_notices.py b/source/isaaclab/isaaclab/cloner/_fabric_notices.py index b3557ef4bd41..513b70d4ccd3 100644 --- a/source/isaaclab/isaaclab/cloner/_fabric_notices.py +++ b/source/isaaclab/isaaclab/cloner/_fabric_notices.py @@ -184,7 +184,13 @@ def disabled_fabric_change_notifies(stage: Usd.Stage, *, restore: bool = True) - return # usdrt only works with a live Kit app — defer import so module load stays cheap. - import usdrt + try: + import usdrt + except ModuleNotFoundError as exc: + if exc.name != "usdrt": + raise + yield + return # Avoid leaking a strong reference into the global ``StageCache`` for stages we did not # author into the cache: ``Insert`` keeps the stage alive for the rest of the process. diff --git a/source/isaaclab/test/sim/test_cloner.py b/source/isaaclab/test/sim/test_cloner.py index 14e30f4970b9..705fd4377c90 100644 --- a/source/isaaclab/test/sim/test_cloner.py +++ b/source/isaaclab/test/sim/test_cloner.py @@ -20,7 +20,7 @@ import pytest import torch -from pxr import UsdGeom +from pxr import Usd, UsdGeom import isaaclab.sim as sim_utils from isaaclab.cloner import ( @@ -120,6 +120,31 @@ def test_usd_replicate_context_queue_and_replicate(sim): assert stage.GetPrimAtPath("/World/envs/env_1/A").IsValid() +def test_disabled_fabric_change_notifies_noops_when_usdrt_unavailable(monkeypatch): + """Fabric notice suspension no-ops when Carbonite bindings exist but ``usdrt`` does not.""" + import builtins + + from isaaclab.cloner import _fabric_notices + + class _FakeBindings: + def validate_with(self, fabric_id: int) -> bool: + raise AssertionError("missing usdrt should prevent fabric-id lookup") + + monkeypatch.setattr(_fabric_notices, "get_bindings", lambda: _FakeBindings()) + + real_import = builtins.__import__ + + def _import_without_usdrt(name, *args, **kwargs): + if name == "usdrt": + raise ModuleNotFoundError("No module named 'usdrt'", name="usdrt") + return real_import(name, *args, **kwargs) + + monkeypatch.setattr(builtins, "__import__", _import_without_usdrt) + + with _fabric_notices.disabled_fabric_change_notifies(Usd.Stage.CreateInMemory()): + pass + + def test_usd_replicate_depth_order_parent_child(sim): """Replicate parent and child when provided out of order; parent should exist before child.""" # Prepare sources diff --git a/source/isaaclab_ovphysx/changelog.d/skip-usd-replication.rst b/source/isaaclab_ovphysx/changelog.d/skip-usd-replication.rst new file mode 100644 index 000000000000..09118ddf8e1d --- /dev/null +++ b/source/isaaclab_ovphysx/changelog.d/skip-usd-replication.rst @@ -0,0 +1,5 @@ +Fixed +^^^^^ + +* Stopped OVPhysX assets from enqueueing redundant USD replication work + during scene cloning. diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py index c075dc8c12a4..e6b28cc8f23b 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/articulation/articulation.py @@ -23,7 +23,6 @@ import isaaclab.sim as sim_utils from isaaclab.assets.articulation.articulation_cfg import ArticulationCfg from isaaclab.assets.articulation.base_articulation import BaseArticulation -from isaaclab.cloner import queue_usd_replication from isaaclab.physics import PhysicsManager from isaaclab.utils.string import resolve_matching_names from isaaclab.utils.wrench_composer import WrenchComposer @@ -86,7 +85,6 @@ def __init__(self, cfg: ArticulationCfg): cfg: A configuration instance. """ super().__init__(cfg) - queue_usd_replication(cfg) queue_ovphysx_replication(cfg) # bindings are populated eagerly in ``_initialize_impl``; the dict # also caches any tensor type the user explicitly queries later diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py index 7a7ab41d364f..10b770e9fa2f 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object/rigid_object.py @@ -20,7 +20,6 @@ from isaaclab.assets.rigid_object.base_rigid_object import BaseRigidObject from isaaclab.assets.rigid_object.rigid_object_cfg import RigidObjectCfg -from isaaclab.cloner import queue_usd_replication from isaaclab.sim.utils.queries import get_all_matching_child_prims, resolve_matching_prims_from_source from isaaclab.utils.string import resolve_matching_names from isaaclab.utils.wrench_composer import WrenchComposer @@ -64,7 +63,6 @@ def __init__(self, cfg: RigidObjectCfg): cfg: A configuration instance. """ super().__init__(cfg) - queue_usd_replication(cfg) queue_ovphysx_replication(cfg) # Bindings are created lazily (on first access) to avoid allocating # handles for tensor types the user never queries. diff --git a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py index 9aea366ad4ee..219e3f95a16c 100644 --- a/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab_ovphysx/isaaclab_ovphysx/assets/rigid_object_collection/rigid_object_collection.py @@ -18,7 +18,6 @@ import isaaclab.sim as sim_utils from isaaclab.assets.rigid_object_collection.base_rigid_object_collection import BaseRigidObjectCollection -from isaaclab.cloner import queue_usd_replication from isaaclab.utils.string import resolve_matching_names from isaaclab.utils.wrench_composer import WrenchComposer @@ -89,7 +88,6 @@ def __init__(self, cfg: RigidObjectCollectionCfg): matching_prims = sim_utils.find_matching_prims(rigid_body_cfg.prim_path) if len(matching_prims) == 0: raise RuntimeError(f"Could not find prim with path {rigid_body_cfg.prim_path}.") - queue_usd_replication(cfg.rigid_objects[rigid_body_name]) queue_ovphysx_replication(cfg.rigid_objects[rigid_body_name]) # stores object names self._body_names_list: list[str] = [] From 31f80ce6b83f969085b79fced5e8f456a09339a2 Mon Sep 17 00:00:00 2001 From: Horde Date: Sat, 6 Jun 2026 06:47:21 +0000 Subject: [PATCH 39/40] Add LEAPP observation-term input boundaries --- .../isaaclab/envs/leapp_deployment_env.py | 107 ++++++++++++++++-- .../isaaclab/utils/leapp/export_annotator.py | 63 ++++++++++- .../isaaclab/utils/leapp/leapp_semantics.py | 34 ++++++ source/isaaclab/isaaclab/utils/leapp/utils.py | 5 + .../contrib/deploy/mdp/observations.py | 7 ++ 5 files changed, 198 insertions(+), 18 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/leapp_deployment_env.py b/source/isaaclab/isaaclab/envs/leapp_deployment_env.py index a2ad5b897647..d5b6409e1553 100644 --- a/source/isaaclab/isaaclab/envs/leapp_deployment_env.py +++ b/source/isaaclab/isaaclab/envs/leapp_deployment_env.py @@ -5,10 +5,10 @@ """Deployment environment that runs LEAPP-exported policies in simulation. -This environment bypasses all Isaac Lab managers (observation, action, reward, etc.) -and instead wires scene entity data properties and ``CommandManager`` outputs directly -to a LEAPP ``InferenceManager``, then writes the model outputs back to the -corresponding scene entities. All I/O resolution is driven by the +This environment bypasses most Isaac Lab managers (action, reward, etc.) and instead +wires scene entity data properties, selected observation terms, and ``CommandManager`` +outputs directly to a LEAPP ``InferenceManager``, then writes the model outputs back +to the corresponding scene entities. All I/O resolution is driven by the ``isaaclab_connection`` field in the LEAPP YAML. """ @@ -27,7 +27,7 @@ except ImportError as e: raise ImportError("LEAPP package is required for policy deployment testing. Install with: pip install leapp") from e -from isaaclab.managers import CommandManager, EventManager +from isaaclab.managers import CommandManager, EventManager, ObservationManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext from isaaclab.sim.utils.stage import use_stage @@ -59,6 +59,14 @@ class CommandInputSpec: command_term_name: str +@dataclass +class ObservationInputSpec: + """Read a named observation term from ``ObservationManager``.""" + + group_name: str + term_name: str + + @dataclass class WriteOutputSpec: """Write a tensor to a scene entity method, optionally indexed by joint.""" @@ -134,6 +142,18 @@ def _first_param_name(method: Any) -> str: return params[0].name +def _leapp_desc_has_connection(leapp_desc: dict[str, Any], connection_type: str) -> bool: + """Return whether a LEAPP description contains an I/O connection of *connection_type*.""" + prefix = f"{connection_type}:" + for model_desc in leapp_desc.get("models", {}).values(): + for io_section in ("inputs", "outputs"): + for tensor_desc in model_desc.get(io_section, []): + connection = tensor_desc.get("isaaclab_connection") + if isinstance(connection, str) and connection.startswith(prefix): + return True + return False + + # ══════════════════════════════════════════════════════════════════ # LeappDeploymentEnv # ══════════════════════════════════════════════════════════════════ @@ -153,10 +173,11 @@ class LeappDeploymentEnv: - ``state:{entity}:{property}`` -- read ``scene[entity].data.{property}`` - ``command:{name}`` -- read ``command_manager.get_command(name)`` + - ``observation:{group}:{term}`` -- compute a named observation term - ``write:{entity}:{method}`` -- call ``scene[entity].{method}(tensor, ...)`` - No observation, action, reward, termination, or curriculum managers are used. - The LEAPP model already contains all pre/post-processing. + No action, reward, termination, or curriculum managers are used. The LEAPP model + already contains all action pre/post-processing. """ def __init__(self, cfg: Any, leapp_yaml_path: str): @@ -197,6 +218,10 @@ def __init__(self, cfg: Any, leapp_yaml_path: str): else: self.viewport_camera_controller = None + # ── Parse YAML once before constructing optional managers ─ + with open(leapp_yaml_path) as f: + self._leapp_desc = yaml.safe_load(f) + # ── EventManager (optional, for resets) ─────────────────── self.event_manager: EventManager | None = None if hasattr(cfg, "events") and cfg.events is not None: @@ -207,13 +232,21 @@ def __init__(self, cfg: Any, leapp_yaml_path: str): if hasattr(cfg, "commands") and cfg.commands is not None: self.command_manager = CommandManager(cfg.commands, cast(Any, self)) + # ── ObservationManager (optional, for observation/* inputs) ─ + self.observation_manager: ObservationManager | None = None + if _leapp_desc_has_connection(self._leapp_desc, "observation"): + if not hasattr(cfg, "observations") or cfg.observations is None: + raise RuntimeError( + "LEAPP YAML declares observation inputs but no ObservationManager configuration is available " + "(cfg.observations is None)." + ) + self.observation_manager = ObservationManager(cfg.observations, cast(Any, self)) + # ── LEAPP InferenceManager ──────────────────────────────── self.inference = InferenceManager(leapp_yaml_path) - # ── Parse YAML and resolve I/O mappings ─────────────────── - with open(leapp_yaml_path) as f: - self._leapp_desc = yaml.safe_load(f) - self._input_mapping: dict[str, StateInputSpec | CommandInputSpec] = {} + # ── Resolve I/O mappings ───────────────────────────────── + self._input_mapping: dict[str, StateInputSpec | CommandInputSpec | ObservationInputSpec] = {} self._output_mapping: dict[str, WriteOutputSpec] = {} self._resolve_io() @@ -286,6 +319,10 @@ def _resolve_io(self): "CommandManager is available (cfg.commands is None)." ) self._input_mapping[key] = CommandInputSpec(command_term_name=command_name) + elif conn_type == "observation": + group_name, term_name = parts[1], parts[2] + self._validate_observation_term(key, group_name, term_name) + self._input_mapping[key] = ObservationInputSpec(group_name=group_name, term_name=term_name) else: logger.warning("Unknown connection type '%s' for input '%s'", conn_type, key) @@ -315,6 +352,27 @@ def _resolve_io(self): else: logger.warning("Unknown connection type '%s' for output '%s'", conn_type, key) + def _validate_observation_term(self, key: str, group_name: str, term_name: str): + """Raise a useful error if a LEAPP observation input cannot be resolved.""" + observation_manager = self.observation_manager + if observation_manager is None: + raise RuntimeError( + f"LEAPP input '{key}' requires observation term '{group_name}:{term_name}' but no " + "ObservationManager is available." + ) + + group_term_names = observation_manager.active_terms.get(group_name) + if group_term_names is None: + raise ValueError( + f"LEAPP input '{key}' references unknown observation group '{group_name}'. " + f"Available groups are: {list(observation_manager.active_terms.keys())}" + ) + if term_name not in group_term_names: + raise ValueError( + f"LEAPP input '{key}' references unknown observation term '{group_name}:{term_name}'. " + f"Available terms in group '{group_name}' are: {group_term_names}" + ) + # ── Read / Write ────────────────────────────────────────────── def _read_inputs(self) -> dict[str, torch.Tensor]: @@ -336,8 +394,29 @@ def _read_inputs(self) -> dict[str, torch.Tensor]: command_manager = self.command_manager assert command_manager is not None inputs[key] = command_manager.get_command(spec.command_term_name) + elif isinstance(spec, ObservationInputSpec): + inputs[key] = self._compute_observation_input(spec) return inputs + def _compute_observation_input(self, spec: ObservationInputSpec) -> torch.Tensor: + """Compute one named observation term without injecting observation noise.""" + observation_manager = self.observation_manager + assert observation_manager is not None + + group_term_names = observation_manager._group_obs_term_names[spec.group_name] + term_index = group_term_names.index(spec.term_name) + term_cfg = observation_manager._group_obs_term_cfgs[spec.group_name][term_index] + + obs: torch.Tensor = term_cfg.func(cast(Any, self), **term_cfg.params).clone() + if term_cfg.modifiers is not None: + for modifier in term_cfg.modifiers: + obs = modifier.func(obs, **modifier.params) + if term_cfg.clip: + obs = obs.clip_(min=term_cfg.clip[0], max=term_cfg.clip[1]) + if term_cfg.scale is not None: + obs = obs.mul_(term_cfg.scale) + return obs + def _write_outputs(self, outputs: dict[str, torch.Tensor]): """Write model outputs to scene entities. @@ -364,12 +443,14 @@ def reset(self) -> dict[str, torch.Tensor]: Returns: The initial input tensors (for logging / debugging). """ - env_ids = [0] + env_ids = torch.arange(self.num_envs, dtype=torch.int32, device=self.device) self.scene.reset(env_ids) if self.event_manager is not None and "reset" in self.event_manager.available_modes: self.event_manager.apply(mode="reset", env_ids=env_ids, global_env_step_count=self._step_count) + if self.observation_manager is not None: + self.observation_manager.reset(env_ids) if self.command_manager is not None: self.command_manager.reset(env_ids) @@ -440,6 +521,8 @@ def close(self): self.sim.stop() if self.command_manager is not None: del self.command_manager + if self.observation_manager is not None: + del self.observation_manager if self.event_manager is not None: del self.event_manager del self.scene diff --git a/source/isaaclab/isaaclab/utils/leapp/export_annotator.py b/source/isaaclab/isaaclab/utils/leapp/export_annotator.py index 3ca82a66c082..adaff2de9f1a 100644 --- a/source/isaaclab/isaaclab/utils/leapp/export_annotator.py +++ b/source/isaaclab/isaaclab/utils/leapp/export_annotator.py @@ -45,11 +45,16 @@ from isaaclab.assets.articulation.base_articulation import BaseArticulation from isaaclab.managers import ManagerTermBase -from .leapp_semantics import select_element_names +from .leapp_semantics import ( + resolve_leapp_element_names, + resolve_leapp_observation_input_semantics, + select_element_names, +) from .proxy import _ArticulationWriteProxy, _DataProxy, _EnvProxy, _ManagerTermProxy from .utils import ( TracedProxyArray, build_command_connection, + build_observation_connection, build_write_connection, ) @@ -129,7 +134,7 @@ def setup(self, env): ) self._disable_training_managers(unwrapped) - self._patch_observation_manager(unwrapped.observation_manager, proxy_env) + self._patch_observation_manager(unwrapped.observation_manager, proxy_env, unwrapped) self._patch_history_buffers(unwrapped.observation_manager) self._patch_action_manager( unwrapped.action_manager, @@ -272,21 +277,34 @@ def patched_append(data: torch.Tensor): circular_buffer._leapp_original_append = original_append circular_buffer._append = patched_append - def _patch_observation_manager(self, obs_manager, proxy_env): + def _patch_observation_manager(self, obs_manager, proxy_env, real_env): """Patch observation terms to use annotating proxies and disable noise. Args: obs_manager: Observation manager instance to patch. proxy_env: Proxy environment routed into observation terms. + real_env: Unwrapped environment used for explicit observation inputs. """ + term_names_by_group = getattr(obs_manager, "_group_obs_term_names", {}) for group_name, term_cfgs in obs_manager._group_obs_term_cfgs.items(): if self.required_obs_groups is not None and group_name not in self.required_obs_groups: continue - for term_cfg in term_cfgs: + group_term_names = term_names_by_group.get(group_name, []) + for index, term_cfg in enumerate(term_cfgs): original_func = term_cfg.func func_name = getattr(original_func, "__name__", None) - - if func_name == "last_action": + term_name = group_term_names[index] if index < len(group_term_names) else func_name + observation_input_semantics = resolve_leapp_observation_input_semantics(original_func) + + if observation_input_semantics is not None: + term_cfg.func = self._wrap_observation_input( + original_func, + real_env, + group_name, + term_name, + observation_input_semantics, + ) + elif func_name == "last_action": self._uses_last_action_state = True term_cfg.func = self._wrap_last_action(original_func) elif func_name == "generated_commands": @@ -308,6 +326,39 @@ def patched_compute(*args, **kwargs): obs_manager.compute = patched_compute + def _wrap_observation_input(self, original_func, real_env, group_name: str, term_name: str, semantics): + """Wrap a full observation term as an explicit LEAPP input tensor. + + Some policy inputs are task-level observation terms, not single raw + scene state properties. Calling the original term with the real env keeps + task-specific computation intact while making the term a live LEAPP + deployment input whenever the term opts in with LEAPP metadata. + """ + task_name = self.task_name + element_names = resolve_leapp_element_names(semantics, original_func) + + def wrapped(*args, **kwargs): + if args: + args = (real_env, *args[1:]) + else: + args = (real_env,) + result = original_func(*args, **kwargs) + sem = TensorSemantics( + name=term_name, + ref=result, + kind=semantics.kind, + element_names=element_names, + extra=build_observation_connection(group_name, term_name), + ) + return annotate.input_tensors(task_name, sem) + + wrapped.__name__ = getattr(original_func, "__name__", term_name) + if hasattr(original_func, "reset"): + wrapped.reset = original_func.reset + if hasattr(original_func, "serialize"): + wrapped.serialize = original_func.serialize + return wrapped + # ── Action manager patches ──────────────────────────────────── def _patch_action_manager(self, action_manager, cache): diff --git a/source/isaaclab/isaaclab/utils/leapp/leapp_semantics.py b/source/isaaclab/isaaclab/utils/leapp/leapp_semantics.py index 340291de16ad..3dce0f8cb076 100644 --- a/source/isaaclab/isaaclab/utils/leapp/leapp_semantics.py +++ b/source/isaaclab/isaaclab/utils/leapp/leapp_semantics.py @@ -90,6 +90,40 @@ def _apply(func: Callable) -> Callable: return _apply +def leapp_observation_input( + *, + kind: Any = None, + element_names: list[str] | list[list[str]] | None = None, + element_names_resolver: Callable | None = None, +) -> Callable: + """Mark an observation term's returned tensor as a named LEAPP input boundary. + + This is intended for observation terms whose deployment interface should be + the final observation value rather than the lower-level scene-state tensors + read inside the term. + """ + + semantics = LeappTensorSemantics( + kind=kind, + element_names=element_names, + element_names_resolver=element_names_resolver, + ) + + def _apply(term: Callable) -> Callable: + term._leapp_observation_input_semantics = semantics + return term + + return _apply + + +def resolve_leapp_observation_input_semantics(term: Any) -> LeappTensorSemantics | None: + """Return LEAPP input-boundary metadata attached to an observation term.""" + semantics = getattr(term, "_leapp_observation_input_semantics", None) + if semantics is not None: + return semantics + return getattr(type(term), "_leapp_observation_input_semantics", None) + + def resolve_leapp_element_names(semantics: LeappTensorSemantics | None, data_self) -> list | None: """Resolve element names from attached semantics and a tensor-producing object.""" if semantics is None: diff --git a/source/isaaclab/isaaclab/utils/leapp/utils.py b/source/isaaclab/isaaclab/utils/leapp/utils.py index 2308f662ab80..7dcff894fc14 100644 --- a/source/isaaclab/isaaclab/utils/leapp/utils.py +++ b/source/isaaclab/isaaclab/utils/leapp/utils.py @@ -82,6 +82,11 @@ def build_command_connection(command_name: str) -> dict[str, str]: return {"isaaclab_connection": f"command:{command_name}"} +def build_observation_connection(group_name: str, term_name: str) -> dict[str, str]: + """Return a compact deployment connection string for an observation term.""" + return {"isaaclab_connection": f"observation:{group_name}:{term_name}"} + + def build_write_connection(entity_name: str, method_name: str) -> dict[str, str]: """Return a compact deployment connection string for an articulation write target.""" return {"isaaclab_connection": f"write:{entity_name}:{method_name}"} diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/mdp/observations.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/mdp/observations.py index ac12d8b22f7f..3e0252ad6ee0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/mdp/observations.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/mdp/observations.py @@ -12,6 +12,11 @@ import torch from isaaclab.managers import ManagerTermBase, ObservationTermCfg, SceneEntityCfg +from isaaclab.utils.leapp.leapp_semantics import ( + QUAT_XYZW_ELEMENT_NAMES, + XYZ_ELEMENT_NAMES, + leapp_observation_input, +) from isaaclab.utils.math import combine_frame_transforms if TYPE_CHECKING: @@ -21,6 +26,7 @@ from .events import randomize_gear_type +@leapp_observation_input(kind="state/body/position", element_names=[XYZ_ELEMENT_NAMES]) class gear_shaft_pos_w(ManagerTermBase): """Gear shaft position in world frame with offset applied. @@ -139,6 +145,7 @@ def __call__( return shaft_pos - env.scene.env_origins +@leapp_observation_input(kind="state/body/rotation", element_names=[QUAT_XYZW_ELEMENT_NAMES]) class gear_shaft_quat_w(ManagerTermBase): """Gear shaft orientation in world frame. From 4fc0d6e2bda939dafbe517532193c643a4783702 Mon Sep 17 00:00:00 2001 From: Horde Date: Mon, 8 Jun 2026 06:37:05 +0000 Subject: [PATCH 40/40] Add LEAPP observation input export docs and tests --- .../exporting_policies_with_leapp.rst | 45 +++++++ .../isaaclab/utils/leapp/__init__.pyi | 6 + .../isaaclab/utils/leapp/export_annotator.py | 25 +++- .../utils/test_leapp_observation_input.py | 118 ++++++++++++++++++ 4 files changed, 190 insertions(+), 4 deletions(-) create mode 100644 source/isaaclab/test/utils/test_leapp_observation_input.py diff --git a/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst b/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst index 8f645757db00..e514bec2e390 100644 --- a/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst +++ b/docs/source/policy_deployment/05_leapp/exporting_policies_with_leapp.rst @@ -188,6 +188,51 @@ configuration are needed. NumPy operations cannot be traced by LEAPP. +Observation-Term Input Boundaries +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +By default, the manager-based export path discovers policy inputs by tracing observation terms +through Isaac Lab proxies. This works well for standard observations that read annotated simulator +state, such as ``robot.data.joint_pos`` or ``robot.data.joint_vel``. In those cases, the exported +LEAPP input is the lower-level simulator state and any PyTorch preprocessing in the observation +term is included in the exported graph. + +Some deployment workflows should expose a higher-level observation term instead of the simulator +or task-internal tensors used to compute it. This is useful when the deployment system already +produces the policy-facing observation value directly, or when the term depends on bookkeeping that +should not become part of the exported runtime interface. In that case, mark the observation term +with ``leapp_observation_input``: + +.. code-block:: python + + from isaaclab.utils.leapp import XYZ_ELEMENT_NAMES, leapp_observation_input + + + @leapp_observation_input(kind="state/body/position", element_names=[XYZ_ELEMENT_NAMES]) + class object_position_w(ManagerTermBase): + ... + +During export, Isaac Lab computes the configured observation term, applies deterministic +post-processing such as modifiers, clipping, and scaling, disables observation noise, and registers +that term value as the LEAPP input boundary. The generated metadata uses an +``observation:{group}:{term}`` connection, for example: + +.. code-block:: text + + observation:policy:gear_shaft_pos + observation:policy:gear_shaft_quat + +When running the exported policy with :class:`~envs.LeappDeploymentEnv`, Isaac Lab constructs an +``ObservationManager`` only when the LEAPP YAML declares ``observation:*`` inputs and computes the +named terms from the task configuration. External runtimes should provide the same term values with +the same ordering, units, frames, and shape used by the policy observation group. + +For example, a gear assembly deployment may provide shaft pose from perception or calibration, +while the training environment computes it from gear type state, fixture offsets, and environment +origins. Marking ``gear_shaft_pos_w`` and ``gear_shaft_quat_w`` with +``leapp_observation_input`` exports those final shaft-pose terms as the policy inputs. + + Verifying an Export ------------------- diff --git a/source/isaaclab/isaaclab/utils/leapp/__init__.pyi b/source/isaaclab/isaaclab/utils/leapp/__init__.pyi index e2b8f497b5f3..061d28ab07d3 100644 --- a/source/isaaclab/isaaclab/utils/leapp/__init__.pyi +++ b/source/isaaclab/isaaclab/utils/leapp/__init__.pyi @@ -20,12 +20,15 @@ __all__ = [ "body_wrench_resolver", "body_xyz_resolver", "build_command_connection", + "build_observation_connection", "build_state_connection", "build_write_connection", "joint_names_resolver", + "leapp_observation_input", "leapp_tensor_semantics", "patch_env_for_export", "resolve_leapp_element_names", + "resolve_leapp_observation_input_semantics", "target_frame_pose_resolver", "target_frame_quat_resolver", "target_frame_xyz_resolver", @@ -48,14 +51,17 @@ from .leapp_semantics import ( body_wrench_resolver, body_xyz_resolver, joint_names_resolver, + leapp_observation_input, leapp_tensor_semantics, resolve_leapp_element_names, + resolve_leapp_observation_input_semantics, target_frame_pose_resolver, target_frame_quat_resolver, target_frame_xyz_resolver, ) from .utils import ( build_command_connection, + build_observation_connection, build_state_connection, build_write_connection, ) diff --git a/source/isaaclab/isaaclab/utils/leapp/export_annotator.py b/source/isaaclab/isaaclab/utils/leapp/export_annotator.py index adaff2de9f1a..a9d562e4960d 100644 --- a/source/isaaclab/isaaclab/utils/leapp/export_annotator.py +++ b/source/isaaclab/isaaclab/utils/leapp/export_annotator.py @@ -303,7 +303,11 @@ def _patch_observation_manager(self, obs_manager, proxy_env, real_env): group_name, term_name, observation_input_semantics, + term_cfg, ) + term_cfg.modifiers = None + term_cfg.clip = None + term_cfg.scale = None elif func_name == "last_action": self._uses_last_action_state = True term_cfg.func = self._wrap_last_action(original_func) @@ -326,13 +330,25 @@ def patched_compute(*args, **kwargs): obs_manager.compute = patched_compute - def _wrap_observation_input(self, original_func, real_env, group_name: str, term_name: str, semantics): + @staticmethod + def _apply_observation_post_processing(obs: torch.Tensor, term_cfg) -> torch.Tensor: + """Apply deterministic observation post-processing configured on a term.""" + if term_cfg.modifiers is not None: + for modifier in term_cfg.modifiers: + obs = modifier.func(obs, **modifier.params) + if term_cfg.clip: + obs = obs.clip_(min=term_cfg.clip[0], max=term_cfg.clip[1]) + if term_cfg.scale is not None: + obs = obs.mul_(term_cfg.scale) + return obs + + def _wrap_observation_input(self, original_func, real_env, group_name: str, term_name: str, semantics, term_cfg): """Wrap a full observation term as an explicit LEAPP input tensor. Some policy inputs are task-level observation terms, not single raw - scene state properties. Calling the original term with the real env keeps - task-specific computation intact while making the term a live LEAPP - deployment input whenever the term opts in with LEAPP metadata. + scene state properties. Calling the original term with the real env and + applying deterministic post-processing keeps the configured observation + boundary intact while making the term a live LEAPP deployment input. """ task_name = self.task_name element_names = resolve_leapp_element_names(semantics, original_func) @@ -343,6 +359,7 @@ def wrapped(*args, **kwargs): else: args = (real_env,) result = original_func(*args, **kwargs) + result = self._apply_observation_post_processing(result, term_cfg) sem = TensorSemantics( name=term_name, ref=result, diff --git a/source/isaaclab/test/utils/test_leapp_observation_input.py b/source/isaaclab/test/utils/test_leapp_observation_input.py new file mode 100644 index 000000000000..ab54148f6ae6 --- /dev/null +++ b/source/isaaclab/test/utils/test_leapp_observation_input.py @@ -0,0 +1,118 @@ +# 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 + +"""Unit tests for LEAPP observation-term input metadata.""" + +from types import SimpleNamespace + +import torch + +import isaaclab.utils.leapp.export_annotator as export_annotator +from isaaclab.utils.leapp import ( + ExportPatcher, + XYZ_ELEMENT_NAMES, + leapp_observation_input, + resolve_leapp_element_names, + resolve_leapp_observation_input_semantics, +) + + +def test_leapp_observation_input_marks_function(): + """Observation input metadata can be attached to function-based terms.""" + + @leapp_observation_input(kind="state/body/position", element_names=[XYZ_ELEMENT_NAMES]) + def observation_term(env): + return None + + semantics = resolve_leapp_observation_input_semantics(observation_term) + + assert semantics is not None + assert semantics.kind == "state/body/position" + assert semantics.element_names == [XYZ_ELEMENT_NAMES] + assert resolve_leapp_element_names(semantics, observation_term) == [XYZ_ELEMENT_NAMES] + + +def test_leapp_observation_input_marks_class_instances(): + """Observation input metadata can be attached to class-based manager terms.""" + + @leapp_observation_input(kind="state/gear/type") + class ObservationTerm: + def __call__(self, env): + return None + + semantics_from_class = resolve_leapp_observation_input_semantics(ObservationTerm) + semantics_from_instance = resolve_leapp_observation_input_semantics(ObservationTerm()) + + assert semantics_from_class is not None + assert semantics_from_class.kind == "state/gear/type" + assert semantics_from_instance is semantics_from_class + + +def test_leapp_observation_input_supports_element_name_resolver(): + """Observation input metadata can resolve element names lazily.""" + + def element_names_resolver(term): + return [term.element_names] + + @leapp_observation_input(kind="state/custom", element_names_resolver=element_names_resolver) + class ObservationTerm: + element_names = ["a", "b", "c"] + + def __call__(self, env): + return None + + term = ObservationTerm() + semantics = resolve_leapp_observation_input_semantics(term) + + assert semantics is not None + assert resolve_leapp_element_names(semantics, term) == [["a", "b", "c"]] + + +def test_leapp_observation_input_wrapper_annotates_processed_term(monkeypatch): + """The export wrapper registers the configured observation value as the LEAPP input.""" + + def add_offset(obs, offset: float): + return obs + offset + + @leapp_observation_input(kind="state/body/position", element_names=[XYZ_ELEMENT_NAMES]) + def observation_term(env, multiplier: float): + return env.value * multiplier + + real_env = SimpleNamespace(value=torch.tensor([[-1.0, 0.25, 2.0]])) + term_cfg = SimpleNamespace( + modifiers=[SimpleNamespace(func=add_offset, params={"offset": 1.0})], + clip=(0.0, 2.0), + scale=3.0, + ) + semantics = resolve_leapp_observation_input_semantics(observation_term) + patcher = ExportPatcher(export_method="onnx") + patcher.task_name = "TestTask-v0" + captured = {} + + def fake_input_tensors(task_name, tensor_semantics): + captured["task_name"] = task_name + captured["tensor_semantics"] = tensor_semantics + return tensor_semantics.ref + + monkeypatch.setattr(export_annotator.annotate, "input_tensors", fake_input_tensors) + + wrapped = patcher._wrap_observation_input( + observation_term, + real_env, + "policy", + "shaft_pos", + semantics, + term_cfg, + ) + returned = wrapped(SimpleNamespace(value=torch.full((1, 3), 100.0)), multiplier=2.0) + + expected = torch.tensor([[0.0, 4.5, 6.0]]) + torch.testing.assert_close(returned, expected) + assert captured["task_name"] == "TestTask-v0" + assert captured["tensor_semantics"].name == "shaft_pos" + assert captured["tensor_semantics"].ref is returned + assert captured["tensor_semantics"].kind == "state/body/position" + assert captured["tensor_semantics"].element_names == [XYZ_ELEMENT_NAMES] + assert captured["tensor_semantics"].extra == {"isaaclab_connection": "observation:policy:shaft_pos"}