diff --git a/apps/isaaclab.python.headless.kit b/apps/isaaclab.python.headless.kit index 12b9e14946d0..e4a8b0a7dde0 100644 --- a/apps/isaaclab.python.headless.kit +++ b/apps/isaaclab.python.headless.kit @@ -173,11 +173,9 @@ folders = [ "${exe-path}/exts", # kit extensions "${exe-path}/extscore", # kit core extensions "${exe-path}/../exts", # isaac extensions - "${exe-path}/../extsDeprecated", # deprecated isaac extensions "${exe-path}/../extscache", # isaac cache extensions "${exe-path}/../extsPhysics", # isaac physics extensions "${exe-path}/../isaacsim/exts", # isaac extensions for pip - "${exe-path}/../isaacsim/extsDeprecated", # deprecated isaac extensions "${exe-path}/../isaacsim/extscache", # isaac cache extensions for pip "${exe-path}/../isaacsim/extsPhysics", # isaac physics extensions for pip "${app}", # needed to find other app files @@ -192,9 +190,7 @@ enabled=true # Enable this for DLSS ######################## [dependencies] "isaacsim.simulation_app" = {} -"isaacsim.core.api" = {} -"isaacsim.core.cloner" = {} -"isaacsim.core.utils" = {} +"isaacsim.core.simulation_manager" = {} "isaacsim.core.version" = {} ######################## diff --git a/apps/isaaclab.python.headless.rendering.kit b/apps/isaaclab.python.headless.rendering.kit index 5247b94b76e4..08ee1ded562a 100644 --- a/apps/isaaclab.python.headless.rendering.kit +++ b/apps/isaaclab.python.headless.rendering.kit @@ -142,11 +142,9 @@ folders = [ "${exe-path}/exts", # kit extensions "${exe-path}/extscore", # kit core extensions "${exe-path}/../exts", # isaac extensions - "${exe-path}/../extsDeprecated", # deprecated isaac extensions "${exe-path}/../extscache", # isaac cache extensions "${exe-path}/../extsPhysics", # isaac physics extensions "${exe-path}/../isaacsim/exts", # isaac extensions for pip - "${exe-path}/../isaacsim/extsDeprecated", # deprecated isaac extensions "${exe-path}/../isaacsim/extscache", # isaac cache extensions for pip "${exe-path}/../isaacsim/extsPhysics", # isaac physics extensions for pip "${app}", # needed to find other app files diff --git a/apps/isaaclab.python.kit b/apps/isaaclab.python.kit index a5330cd1944e..dad8a1e72808 100644 --- a/apps/isaaclab.python.kit +++ b/apps/isaaclab.python.kit @@ -14,23 +14,26 @@ keywords = ["experience", "app", "usd"] # Isaac Sim extensions "isaacsim.app.about" = {} "isaacsim.examples.browser" = {} -"isaacsim.core.api" = {} "isaacsim.core.cloner" = {} +"isaacsim.core.deprecation_manager" = { order = -100 } +"isaacsim.core.experimental.materials" = {} +"isaacsim.core.experimental.objects" = {} +"isaacsim.core.experimental.primdata" = {} +"isaacsim.core.experimental.prims" = {} +"isaacsim.core.experimental.utils" = {} "isaacsim.core.nodes" = {} +"isaacsim.core.rendering_manager" = {} +"isaacsim.core.simulation_manager" = {} "isaacsim.core.throttling" = {} -"isaacsim.core.utils" = {} "isaacsim.core.version" = {} -"isaacsim.gui.menu" = {} "isaacsim.gui.property" = {} "isaacsim.replicator.behavior" = {} -"isaacsim.robot.manipulators" = {} "isaacsim.robot.policy.examples" = {} "isaacsim.robot.schema" = {} -"isaacsim.robot.wheeled_robots" = {} -"isaacsim.sensors.camera" = {} -"isaacsim.sensors.physics" = {} -"isaacsim.sensors.physx" = {} -"isaacsim.sensors.rtx" = {} +"isaacsim.robot.experimental.wheeled_robots" = {} +"isaacsim.robot.wheeled_robots.nodes" = {} +"isaacsim.sensors.experimental.physics" = {} +"isaacsim.sensors.experimental.rtx" = {} "isaacsim.simulation_app" = {} "isaacsim.storage.native" = {} "isaacsim.util.debug_draw" = {} @@ -273,11 +276,9 @@ folders = [ "${exe-path}/exts", # kit extensions "${exe-path}/extscore", # kit core extensions "${exe-path}/../exts", # isaac extensions - "${exe-path}/../extsDeprecated", # deprecated isaac extensions "${exe-path}/../extscache", # isaac cache extensions "${exe-path}/../extsPhysics", # isaac physics extensions "${exe-path}/../isaacsim/exts", # isaac extensions for pip - "${exe-path}/../isaacsim/extsDeprecated", # deprecated isaac extensions "${exe-path}/../isaacsim/extscache", # isaac cache extensions for pip "${exe-path}/../isaacsim/extsPhysics", # isaac physics extensions for pip "${app}", # needed to find other app files diff --git a/apps/isaaclab.python.rendering.kit b/apps/isaaclab.python.rendering.kit index d3414b211907..9094bcad4b9f 100644 --- a/apps/isaaclab.python.rendering.kit +++ b/apps/isaaclab.python.rendering.kit @@ -126,11 +126,9 @@ folders = [ "${exe-path}/exts", # kit extensions "${exe-path}/extscore", # kit core extensions "${exe-path}/../exts", # isaac extensions - "${exe-path}/../extsDeprecated", # deprecated isaac extensions "${exe-path}/../extscache", # isaac cache extensions "${exe-path}/../extsPhysics", # isaac physics extensions "${exe-path}/../isaacsim/exts", # isaac extensions for pip - "${exe-path}/../isaacsim/extsDeprecated", # deprecated isaac extensions "${exe-path}/../isaacsim/extscache", # isaac cache extensions for pip "${exe-path}/../isaacsim/extsPhysics", # isaac physics extensions for pip "${app}", # needed to find other app files diff --git a/apps/isaaclab.python.xr.openxr.headless.kit b/apps/isaaclab.python.xr.openxr.headless.kit index 75f3ae637124..b3516dda71f4 100644 --- a/apps/isaaclab.python.xr.openxr.headless.kit +++ b/apps/isaaclab.python.xr.openxr.headless.kit @@ -56,11 +56,9 @@ folders = [ "${exe-path}/extscore", # kit core extensions "${exe-path}/../exts", # isaac extensions "${exe-path}/../extsInternal", # isaac internal extensions - "${exe-path}/../extsDeprecated", # deprecated isaac extensions "${exe-path}/../extscache", # isaac cache extensions "${exe-path}/../extsPhysics", # isaac physics extensions "${exe-path}/../isaacsim/exts", # isaac extensions for pip - "${exe-path}/../isaacsim/extsDeprecated", # deprecated isaac extensions "${exe-path}/../isaacsim/extscache", # isaac cache extensions for pip "${exe-path}/../isaacsim/extsPhysics", # isaac physics extensions for pip "${app}", # needed to find other app files diff --git a/apps/isaaclab.python.xr.openxr.kit b/apps/isaaclab.python.xr.openxr.kit index 62782ba06619..7ff3f9861c7a 100644 --- a/apps/isaaclab.python.xr.openxr.kit +++ b/apps/isaaclab.python.xr.openxr.kit @@ -80,11 +80,9 @@ folders = [ "${exe-path}/extscore", # kit core extensions "${exe-path}/../exts", # isaac extensions "${exe-path}/../extsInternal", # isaac internal extensions - "${exe-path}/../extsDeprecated", # deprecated isaac extensions "${exe-path}/../extscache", # isaac cache extensions "${exe-path}/../extsPhysics", # isaac physics extensions "${exe-path}/../isaacsim/exts", # isaac extensions for pip - "${exe-path}/../isaacsim/extsDeprecated", # deprecated isaac extensions "${exe-path}/../isaacsim/extscache", # isaac cache extensions for pip "${exe-path}/../isaacsim/extsPhysics", # isaac physics extensions for pip "${app}", # needed to find other app files diff --git a/docs/conf.py b/docs/conf.py index 510fa3bc9280..260e71688f23 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -173,11 +173,11 @@ "pxr.PhysxSchema", "pxr.PhysicsSchemaTools", "omni.replicator", - "isaacsim", - "isaacsim.core.api", "isaacsim.core.cloner", "isaacsim.core.version", - "isaacsim.core.utils", + "isaacsim.core.experimental.prims", + "isaacsim.core.experimental.utils", + "isaacsim.core.rendering_manager", "isaacsim.robot_motion.motion_generation", "isaacsim.gui.components", "isaacsim.asset.importer.urdf", diff --git a/docs/source/migration/migrating_to_isaaclab_3-0.rst b/docs/source/migration/migrating_to_isaaclab_3-0.rst index 6787a42766ef..b714257797b0 100644 --- a/docs/source/migration/migrating_to_isaaclab_3-0.rst +++ b/docs/source/migration/migrating_to_isaaclab_3-0.rst @@ -1672,6 +1672,123 @@ Deprecated retargeters have been moved to ``isaaclab_teleop.deprecated.openxr.re compatibility. These will be removed in a future release. +Migration off Deprecated Isaac Sim APIs +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +In Isaac Sim 6.0, the legacy ``isaacsim.core.*``, ``isaacsim.sensors.*``, and +``isaacsim.robot.wheeled_robots`` Python module paths are **deprecated** in favor of their +``isaacsim.core.experimental.*`` (and ``*.experimental.*``) equivalents. Isaac Lab 3.0 has +been migrated off the deprecated paths so that Isaac Lab continues to load and run when +those modules are removed in a future Isaac Sim release. + +This is mostly a transparent change for users — Isaac Lab's own public Python API +(:mod:`isaaclab`, :mod:`isaaclab_physx`, :mod:`isaaclab_tasks`, :mod:`isaaclab_teleop`, +:mod:`isaaclab_mimic`) is unchanged. The migration is only user-visible if you: + +1. Import Isaac Sim symbols **directly** in your project, or +2. Maintain a custom Kit experience (``.kit`` file) that lists Isaac Sim extension + dependencies, or +3. Imported ``SimulationManager`` from ``isaacsim.core.simulation_manager`` in your own + PhysX-backed code. + + +Python module renames +--------------------- + +Update direct imports in your own code as follows. **Where Isaac Lab provides an in-tree +replacement, prefer the Isaac Lab API** over the ``isaacsim.core.experimental.*`` fallback: + +.. list-table:: + :header-rows: 1 + :widths: 45 55 + + * - Deprecated Isaac Sim path + - Recommended replacement + * - ``isaacsim.core.utils.stage`` + - :mod:`isaaclab.sim.utils.stage` (e.g. ``get_current_stage``, + ``create_new_stage``, ``open_stage``, ``save_stage``, ``close_stage``, + ``clear_stage``, ``update_stage``, ``use_stage``) + * - ``isaacsim.core.utils.prims`` + - :mod:`isaaclab.sim.utils.prims` (e.g. ``create_prim``, ``delete_prim``, + ``change_prim_property``, ``bind_visual_material``, + ``bind_physics_material``, ``add_usd_reference``) + * - ``isaacsim.core.utils.queries`` + - :mod:`isaaclab.sim.utils.queries` (e.g. ``find_matching_prims``, + ``find_matching_prim_paths``, ``get_first_matching_child_prim``) + * - ``isaacsim.core.utils.transforms`` + - :mod:`isaaclab.sim.utils.transforms` + * - ``isaacsim.core.utils.semantics`` + - :mod:`isaaclab.sim.utils.semantics` + * - ``isaacsim.core.utils.extensions.enable_extension`` + - ``isaacsim.core.experimental.utils.app.enable_extension`` (no Isaac Lab equivalent) + * - ``isaacsim.core.utils.viewports.set_camera_view`` + - ``isaacsim.core.rendering_manager.ViewportManager.set_camera_view`` (or + ``omni.kit.viewport.utility.camera_state.ViewportCameraState`` for lower-level control) + * - ``isaacsim.core.prims.XFormPrim`` / ``XFormPrimView`` + - :class:`~isaaclab.sim.views.FrameView` (Isaac Lab in-tree view; see + :ref:`migrating-to-isaaclab-3-0` ``Renaming of XformPrimView to FrameView`` above). + For ``Articulation`` / ``RigidPrim`` use ``isaacsim.core.experimental.prims``. + * - ``isaacsim.core.simulation_manager.SimulationManager`` + - :class:`isaaclab_physx.physics.PhysxManager` (PhysX backend) or + ``isaaclab_newton.physics.NewtonManager`` (Newton backend); see local-alias + pattern below. + * - ``isaacsim.core.cloner`` + - :mod:`isaaclab.cloner` (Isaac Lab in-tree cloner) + * - ``isaacsim.replicator.mobility_gen`` + - ``isaacsim.replicator.experimental.mobility_gen`` + * - ``isaacsim.sensors.`` + - ``isaacsim.sensors.experimental.`` + * - ``isaacsim.robot.wheeled_robots`` + - ``isaacsim.robot.experimental.wheeled_robots`` (and + ``isaacsim.robot.wheeled_robots.nodes`` for OmniGraph nodes) + +To keep call-site code symmetric across backends when migrating off +``isaacsim.core.simulation_manager.SimulationManager``, use the local-alias pattern: + +.. code-block:: python + + from isaaclab_physx.physics import PhysxManager as SimulationManager + # or, for the Newton backend + from isaaclab_newton.physics import NewtonManager as SimulationManager + + +Kit experience (``.kit``) updates +--------------------------------- + +If you maintain a custom Kit experience derived from one of the Isaac Lab apps under +``apps/``: + +* **Stop registering deprecated extension search paths.** The ``extsDeprecated`` search + path entry has been removed from all stock Isaac Lab Kit experiences (headless, + rendering, XR variants). Mirror that change in your own experience. +* **Switch explicit Isaac Sim extension dependencies** to the non-deprecated equivalents + listed above (``isaacsim.core.experimental.*``, ``isaacsim.sensors.experimental.*``, + ``isaacsim.robot.experimental.wheeled_robots``). +* **Remove unused Isaac Sim extensions that pull in** ``isaacsim.core.api`` — Isaac Lab + no longer depends on those, and keeping them resurrects the deprecated stack. + + +``SimulationManager`` is no longer re-exported +---------------------------------------------- + +Earlier internal previews of this migration briefly exposed +``isaaclab_physx.physics.SimulationManager`` as a public alias of +:class:`~isaaclab_physx.physics.PhysxManager`. **That alias has been removed**; use +:class:`~isaaclab_physx.physics.PhysxManager` directly (with ``as SimulationManager`` at +the import site if you want backend-agnostic call-site code, as shown above). + + +Retired standalone reproducers +------------------------------ + +A handful of legacy reproducers under ``source/isaaclab/test/deps/isaacsim`` that +depended on the deprecated Isaac Sim core extensions have been retired: +``check_camera.py``, ``check_floating_base_made_fixed.py``, +``check_legged_robot_clone.py``, ``check_rep_texture_randomizer.py``, and +``check_ref_count.py``. Use :mod:`isaaclab.sim` together with the new +``isaacsim.core.experimental.*`` APIs for the same debugging workflows. + + PhysX Tensors API Module Path ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/source/overview/core-concepts/sensors/ray_caster.rst b/docs/source/overview/core-concepts/sensors/ray_caster.rst index 8b2f12020b3f..9b6ce1a31373 100644 --- a/docs/source/overview/core-concepts/sensors/ray_caster.rst +++ b/docs/source/overview/core-concepts/sensors/ray_caster.rst @@ -50,7 +50,7 @@ Querying the sensor for data can be done at simulation run time like any other s ------------------------------- Ray-caster @ '/World/envs/env_.*/Robot/base/lidar_cage': - view type : + view type : update period (s) : 0.016666666666666666 number of meshes : 1 number of sensors : 1 diff --git a/docs/source/overview/imitation-learning/humanoids_imitation.rst b/docs/source/overview/imitation-learning/humanoids_imitation.rst index 56f6a28c81b8..597fe629d4e4 100644 --- a/docs/source/overview/imitation-learning/humanoids_imitation.rst +++ b/docs/source/overview/imitation-learning/humanoids_imitation.rst @@ -563,7 +563,7 @@ To generate the locomanipulation dataset, use the following command: ./isaaclab.sh -p \ scripts/imitation_learning/locomanipulation_sdg/generate_data.py \ --device cpu \ - --kit_args="--enable isaacsim.replicator.mobility_gen" \ + --kit_args="--enable isaacsim.replicator.experimental.mobility_gen" \ --task="Isaac-G1-SteeringWheel-Locomanipulation" \ --dataset ./datasets/generated_dataset_g1_locomanip.hdf5 \ --num_runs 1 \ @@ -736,7 +736,7 @@ Download the files and place them under ````, then run the fo ./isaaclab.sh -p scripts/imitation_learning/locomanipulation_sdg/generate_data.py \ --device cpu \ - --kit_args="--enable isaacsim.replicator.mobility_gen" \ + --kit_args="--enable isaacsim.replicator.experimental.mobility_gen" \ --task="Isaac-G1-SteeringWheel-Locomanipulation" \ --dataset /dataset_annotated_g1_locomanip.hdf5 \ --num_runs 1 \ diff --git a/docs/source/setup/installation/include/bin_verify_isaacsim.rst b/docs/source/setup/installation/include/bin_verify_isaacsim.rst index 19da95e16236..4d5bbd1f5a0d 100644 --- a/docs/source/setup/installation/include/bin_verify_isaacsim.rst +++ b/docs/source/setup/installation/include/bin_verify_isaacsim.rst @@ -34,7 +34,7 @@ Check that the simulator runs from a standalone python script: # checks that python path is set correctly ${ISAACSIM_PYTHON_EXE} -c "print('Isaac Sim configuration is now complete.')" # checks that Isaac Sim can be launched from python - ${ISAACSIM_PYTHON_EXE} ${ISAACSIM_PATH}/standalone_examples/api/isaacsim.core.api/add_cubes.py + ${ISAACSIM_PYTHON_EXE} ${ISAACSIM_PATH}/standalone_examples/api/isaacsim.core.experimental.api/add_cubes.py .. tab-item:: :icon:`fa-brands fa-windows` Windows :sync: windows @@ -44,7 +44,7 @@ Check that the simulator runs from a standalone python script: :: checks that python path is set correctly %ISAACSIM_PYTHON_EXE% -c "print('Isaac Sim configuration is now complete.')" :: checks that Isaac Sim can be launched from python - %ISAACSIM_PYTHON_EXE% %ISAACSIM_PATH%\standalone_examples\api\isaacsim.core.api\add_cubes.py + %ISAACSIM_PYTHON_EXE% %ISAACSIM_PATH%\standalone_examples\api\isaacsim.core.experimental.api\add_cubes.py .. caution:: diff --git a/docs/source/tutorials/00_sim/create_empty.rst b/docs/source/tutorials/00_sim/create_empty.rst index a659e6da5de5..e65876a0f997 100644 --- a/docs/source/tutorials/00_sim/create_empty.rst +++ b/docs/source/tutorials/00_sim/create_empty.rst @@ -72,8 +72,8 @@ pausing and stepping the simulator. All these operations are handled through the context**. It takes care of various timeline events and also configures the physics scene for simulation. -In Isaac Lab, the :class:`sim.SimulationContext` class inherits from Isaac Sim's -:class:`isaacsim.core.api.simulation_context.SimulationContext` to allow configuring the simulation +In Isaac Lab, the :class:`sim.SimulationContext` class wraps Isaac Sim's simulation stack +to allow configuring the simulation through Python's ``dataclass`` object and handle certain intricacies of the simulation stepping. For this tutorial, we set the physics and rendering time step to 0.01 seconds. This is done diff --git a/docs/source/tutorials/00_sim/launch_app.rst b/docs/source/tutorials/00_sim/launch_app.rst index 62e77c49612c..8c2670e8f605 100644 --- a/docs/source/tutorials/00_sim/launch_app.rst +++ b/docs/source/tutorials/00_sim/launch_app.rst @@ -128,7 +128,7 @@ as we will demonstrate later in this tutorial. These arguments can be used with any script that starts the simulation using :class:`~app.AppLauncher`, with one exception, ``--enable_cameras``. This setting sets the rendering pipeline to use the offscreen renderer. However, this setting is only compatible with the :class:`isaaclab.sim.SimulationContext`. -It will not work with Isaac Sim's :class:`isaacsim.core.api.simulation_context.SimulationContext` class. +It will not work with Isaac Sim's legacy ``SimulationContext`` from deprecated Isaac Sim core extensions. For more information on this flag, please see the :class:`~app.AppLauncher` API documentation. diff --git a/scripts/environments/state_machine/lift_teddy_bear.py b/scripts/environments/state_machine/lift_teddy_bear.py index 47a6c91cd197..dd6574049dbe 100644 --- a/scripts/environments/state_machine/lift_teddy_bear.py +++ b/scripts/environments/state_machine/lift_teddy_bear.py @@ -34,9 +34,9 @@ simulation_app = app_launcher.app # disable metrics assembler due to scene graph instancing -from isaacsim.core.utils.extensions import disable_extension +from isaacsim.core.experimental.utils.app import enable_extension -disable_extension("omni.usd.metrics.assembler.ui") +enable_extension("omni.usd.metrics.assembler.ui", enabled=False) """Rest everything else.""" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 3c383add2e7b..544a6c4ab1b7 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -15,6 +15,19 @@ Changed 4.6.14 (2026-04-24) ~~~~~~~~~~~~~~~~~~~ +Changed +^^^^^^^ + +* Updated the :class:`~isaaclab.cloner.TemplateCloneCfg` docstring example to import + ``get_current_stage`` from :mod:`isaaclab.sim.utils.stage` instead of + ``isaacsim.core.experimental.utils.stage``, aligning with the Isaac Lab API. +* Added a "Migration off Deprecated Isaac Sim APIs" section to the Isaac Lab 3.0 + migration guide (``docs/source/migration/migrating_to_isaaclab_3-0.rst``) that maps + deprecated ``isaacsim.core.*`` paths to their recommended replacements, preferring + Isaac Lab in-tree APIs (``isaaclab.sim.utils.*``, :class:`~isaaclab.sim.views.FrameView`, + :mod:`~isaaclab.cloner`) over the ``isaacsim.core.experimental.*`` fallbacks where + an Isaac Lab API exists. + Fixed ^^^^^ @@ -32,6 +45,18 @@ Fixed 4.6.13 (2026-04-22) ~~~~~~~~~~~~~~~~~~~ +Changed +^^^^^^^ + +* Updated cross-backend asset interface tests to import :class:`~isaaclab_physx.physics.PhysxManager` + (aliased as ``SimulationManager``) instead of ``isaacsim.core.simulation_manager.SimulationManager``. +* Stopped registering deprecated Isaac Sim extension search paths in Isaac Lab Kit experiences and + switched explicit Isaac Sim extension dependencies to non-deprecated ``isaacsim.core.experimental.*``, + ``isaacsim.robot.experimental.wheeled_robots``, ``isaacsim.robot.wheeled_robots.nodes``, and + ``isaacsim.sensors.experimental.*`` equivalents. +* Migrated remaining Isaac Lab imports off deprecated Isaac Sim core utility/prim Python module paths + to their ``isaacsim.core.experimental.*`` replacements. + Fixed ^^^^^ @@ -43,6 +68,13 @@ Fixed installing the Isaac Lab submodules and force-reinstalls the cmeel ``pin``/``pin-pink``/ ``daqp`` stack when the probe fails. +Removed +^^^^^^^ + +* Retired several ``source/isaaclab/test/deps/isaacsim`` standalone reproducers that depended on + deprecated Isaac Sim core extensions; use :mod:`isaaclab.sim` and ``isaacsim.core.experimental.*`` + for similar debugging workflows. + 4.6.12 (2026-04-23) ~~~~~~~~~~~~~~~~~~~ @@ -230,7 +262,6 @@ Fixed :func:`~isaaclab.cloner.cloner_utils.clone_from_template`, keeping downstream order stable across simulation and visualization backends. - 4.6.6 (2026-04-17) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/cloner/cloner_cfg.py b/source/isaaclab/isaaclab/cloner/cloner_cfg.py index 72887017cfe6..23983a389951 100644 --- a/source/isaaclab/isaaclab/cloner/cloner_cfg.py +++ b/source/isaaclab/isaaclab/cloner/cloner_cfg.py @@ -34,7 +34,7 @@ class TemplateCloneCfg: .. code-block:: python from isaaclab.cloner import TemplateCloneCfg, clone_from_template - from isaacsim.core.utils.stage import get_current_stage + from isaaclab.sim.utils.stage import get_current_stage stage = get_current_stage() cfg = TemplateCloneCfg( diff --git a/source/isaaclab/isaaclab/controllers/rmp_flow.py b/source/isaaclab/isaaclab/controllers/rmp_flow.py index e8f456eb10e1..f5be9b0bb274 100644 --- a/source/isaaclab/isaaclab/controllers/rmp_flow.py +++ b/source/isaaclab/isaaclab/controllers/rmp_flow.py @@ -11,7 +11,7 @@ import torch # enable motion generation extensions -from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name +from isaacsim.core.experimental.utils.app import enable_extension, get_extension_path enable_extension("isaacsim.robot_motion.lula") enable_extension("isaacsim.robot_motion.motion_generation") @@ -37,7 +37,7 @@ def _resolve_rmpflow_path(path: str) -> str: """ if path.startswith(_RMPFLOW_EXT_PREFIX): rel = path[len(_RMPFLOW_EXT_PREFIX) :] - ext_dir = get_extension_path_from_name(_RMPFLOW_EXT_NAME) + ext_dir = get_extension_path(_RMPFLOW_EXT_NAME) return os.path.join(ext_dir, rel) return path diff --git a/source/isaaclab/isaaclab/controllers/utils.py b/source/isaaclab/isaaclab/controllers/utils.py index fc091d324af8..879e82fe69d3 100644 --- a/source/isaaclab/isaaclab/controllers/utils.py +++ b/source/isaaclab/isaaclab/controllers/utils.py @@ -26,7 +26,7 @@ def convert_usd_to_urdf(usd_path: str, output_path: str, force_conversion: bool Returns: A tuple containing the paths to the URDF file and the mesh directory. """ - from isaacsim.core.utils.extensions import enable_extension + from isaacsim.core.experimental.utils.app import enable_extension enable_extension("isaacsim.asset.exporter.urdf") diff --git a/source/isaaclab/isaaclab/envs/mdp/events.py b/source/isaaclab/isaaclab/envs/mdp/events.py index 06e5e5bb1c32..9113eb6e4a7a 100644 --- a/source/isaaclab/isaaclab/envs/mdp/events.py +++ b/source/isaaclab/isaaclab/envs/mdp/events.py @@ -2049,7 +2049,7 @@ def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv): ) # enable replicator extension if not already enabled (local: isaacsim only available with Kit) - from isaacsim.core.utils.extensions import enable_extension # noqa: PLC0415 + from isaacsim.core.experimental.utils.app import enable_extension # noqa: PLC0415 enable_extension("omni.replicator.core") # we import the module here since we may not always need the replicator @@ -2220,7 +2220,7 @@ def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv): super().__init__(cfg, env) # enable replicator extension if not already enabled (local: isaacsim only available with Kit) - from isaacsim.core.utils.extensions import enable_extension # noqa: PLC0415 + from isaacsim.core.experimental.utils.app import enable_extension # noqa: PLC0415 enable_extension("omni.replicator.core") # we import the module here since we may not always need the replicator diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py index 6d2df6285e05..74ba8b470c3a 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py @@ -9,7 +9,7 @@ import omni import omni.kit.commands -from isaacsim.core.utils.extensions import enable_extension +from isaacsim.core.experimental.utils.app import enable_extension from pxr import Gf, Tf, Usd, UsdGeom, UsdPhysics, UsdUtils from isaaclab.sim.converters.asset_converter_base import AssetConverterBase diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py index eb2b54d57cbd..3b2f5eb15a9e 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -123,7 +123,7 @@ def _modify_path(asset_path: str) -> str: # _context is a singleton design in isaacsim and for that reason # until we fully replace all modules that references the singleton(such as XformPrim, Prim ....), we have to point # that singleton to this _context - from isaacsim.core.utils import stage as sim_stage + from isaacsim.core.experimental.utils import stage as sim_stage sim_stage._context = _context # type: ignore except ImportError: @@ -136,7 +136,7 @@ def create_new_stage() -> Usd.Stage: Creates a new stage using pure USD (``Usd.Stage.CreateInMemory()``). If Kit is running and Kit extensions need to discover this stage (e.g. - PhysX, ``isaacsim.core.prims.Articulation``), call + PhysX, ``isaacsim.core.experimental.prims.Articulation``), call :func:`attach_stage_to_usd_context` after scene setup. Returns: diff --git a/source/isaaclab/isaaclab/test/benchmark/benchmark_core.py b/source/isaaclab/isaaclab/test/benchmark/benchmark_core.py index bf6e66495d6c..7daedbc132a8 100644 --- a/source/isaaclab/isaaclab/test/benchmark/benchmark_core.py +++ b/source/isaaclab/isaaclab/test/benchmark/benchmark_core.py @@ -119,7 +119,7 @@ def __init__( if self._use_frametime_recorders: try: # Enable the benchmark services extension first - from isaacsim.core.utils.extensions import enable_extension + from isaacsim.core.experimental.utils.app import enable_extension enable_extension("isaacsim.benchmark.services") diff --git a/source/isaaclab/test/assets/test_articulation_iface.py b/source/isaaclab/test/assets/test_articulation_iface.py index cbec2781065b..9edc02656266 100644 --- a/source/isaaclab/test/assets/test_articulation_iface.py +++ b/source/isaaclab/test/assets/test_articulation_iface.py @@ -48,7 +48,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab/test/assets/test_rigid_object_collection_iface.py b/source/isaaclab/test/assets/test_rigid_object_collection_iface.py index 143d32a7f3ba..c047329d0885 100644 --- a/source/isaaclab/test/assets/test_rigid_object_collection_iface.py +++ b/source/isaaclab/test/assets/test_rigid_object_collection_iface.py @@ -38,7 +38,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab/test/assets/test_rigid_object_iface.py b/source/isaaclab/test/assets/test_rigid_object_iface.py index 1dc89d2c4c54..085005627b79 100644 --- a/source/isaaclab/test/assets/test_rigid_object_iface.py +++ b/source/isaaclab/test/assets/test_rigid_object_iface.py @@ -38,7 +38,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 34ae911ac911..a56545d31fd8 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -16,9 +16,8 @@ import torch import warp as wp -from isaacsim.core.cloner import GridCloner - import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg @@ -53,18 +52,15 @@ def sim(): cfg = sim_utils.GroundPlaneCfg() cfg.func("/World/GroundPlane", cfg) - # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=stage) - cloner.define_base_env("/World/envs") - env_prim_paths = cloner.generate_paths("/World/envs/env", num_envs) + # Create environment clones using Isaac Lab's cloner utilities + env_prim_paths = [f"/World/envs/env_{i}" for i in range(num_envs)] + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_envs, dtype=torch.long, device=sim.device) + env_origins, _ = cloner.grid_transforms(num_envs, spacing=2.0, device=sim.device) # create source prim stage.DefinePrim(env_prim_paths[0], "Xform") # clone the env xform - cloner.clone( - source_prim_path=env_prim_paths[0], - prim_paths=env_prim_paths, - replicate_physics=True, - ) + cloner.usd_replicate(stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) # Define goals for the arm (x, y, z, qx, qy, qz, qw) ee_goals_set = [ diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index 3b9eb1a2c5a0..49a7efd425d3 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -17,10 +17,9 @@ import warp as wp from flaky import flaky -from isaacsim.core.cloner import GridCloner - import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.assets import Articulation from isaaclab.assets.articulation import ArticulationCfg from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg @@ -82,18 +81,15 @@ def sim(): translation=[0, 0, 1], ) - # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=stage) - cloner.define_base_env("/World/envs") - env_prim_paths = cloner.generate_paths("/World/envs/env", num_envs) + # Create environment clones using Isaac Lab's cloner utilities + env_prim_paths = [f"/World/envs/env_{i}" for i in range(num_envs)] + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_envs, dtype=torch.long, device=sim.device) + env_origins, _ = cloner.grid_transforms(num_envs, spacing=2.0, device=sim.device) # create source prim stage.DefinePrim(env_prim_paths[0], "Xform") # clone the env xform - cloner.clone( - source_prim_path=env_prim_paths[0], - prim_paths=env_prim_paths, - replicate_physics=True, - ) + cloner.usd_replicate(stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) robot_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/envs/env_.*/Robot") robot_cfg.actuators["panda_shoulder"].stiffness = 0.0 diff --git a/source/isaaclab/test/deps/isaacsim/check_camera.py b/source/isaaclab/test/deps/isaacsim/check_camera.py index 27a0dfdfca99..ee2c9d5adf28 100644 --- a/source/isaaclab/test/deps/isaacsim/check_camera.py +++ b/source/isaaclab/test/deps/isaacsim/check_camera.py @@ -3,241 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -""" -This script shows the issue with renderer in Isaac Sim that affects episodic resets. +"""Historic camera episodic-reset reproducer (retired). -The first few images of every new episode are not updated. They take multiple steps to update -and have the same image as the previous episode for the first few steps. +This script previously depended on Isaac Sim core extensions that Isaac Sim now carries under +``source/deprecated`` in the Isaac Sim repository. It has been retired from Isaac Lab to avoid +depending on those extension IDs and import paths. -``` -# run with cube -_isaac_sim/python.sh source/isaaclab/test/deps/isaacsim/check_camera.py --scenario cube -# run with anymal -_isaac_sim/python.sh source/isaaclab/test/deps/isaacsim/check_camera.py --scenario anymal -``` +Use :class:`~isaaclab.sim.SimulationContext`, Isaac Lab sensors, and ``isaacsim.core.experimental.*`` +APIs when debugging rendering and camera pipelines. """ -"""Launch Isaac Sim Simulator first.""" - -import argparse - -# isaaclab -from isaaclab.app import AppLauncher - -# add argparse arguments -parser = argparse.ArgumentParser( - description="This script shows the issue with renderer in Isaac Sim that affects episodic resets." +raise RuntimeError( + "This standalone reproducer was retired; it depended on deprecated Isaac Sim core extensions. " + "Use Isaac Lab :mod:`isaaclab.sim` and ``isaacsim.core.experimental.*`` instead." ) -parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.") -parser.add_argument("--scenario", type=str, default="anymal", help="Scenario to load.", choices=["anymal", "cube"]) -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# 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 os -import random - -import numpy as np -from PIL import Image, ImageChops - -import isaacsim.core.utils.nucleus as nucleus_utils -import isaacsim.core.utils.prims as prim_utils -import omni.replicator.core as rep -from isaacsim.core.api.world import World -from isaacsim.core.prims import Articulation, RigidPrim, SingleGeometryPrim, SingleRigidPrim -from isaacsim.core.utils.viewports import set_camera_view -from pxr import Gf, UsdGeom - -# check nucleus connection -if nucleus_utils.get_assets_root_path() is None: - msg = ( - "Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n" - "\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus" - ) - raise RuntimeError(msg) - -ISAAC_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac" -"""Path to the `Isaac` directory on the NVIDIA Nucleus Server.""" - - -def main(): - """Runs a camera sensor from isaaclab.""" - - # Load kit helper - world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu") - # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) - - # Enable flatcache which avoids passing data over to USD structure - # this speeds up the read-write operation of GPU buffers - if world.get_physics_context().use_gpu_pipeline: - world.get_physics_context().enable_flatcache(True) - # Enable hydra scene-graph instancing - # this is needed to visualize the scene when flatcache is enabled - world._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) - - # Populate scene - # Ground - world.scene.add_default_ground_plane() - # Lights-1 - prim_utils.create_prim("/World/Light/GreySphere", "SphereLight", translation=(4.5, 3.5, 10.0)) - # Lights-2 - prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0)) - # Xform to hold objects - if args_cli.scenario == "cube": - prim_utils.create_prim("/World/Objects", "Xform") - # Random objects - for i in range(8): - # sample random position - position = np.random.rand(3) - np.asarray([0.05, 0.05, -1.0]) - position *= np.asarray([1.5, 1.5, 0.5]) - # create prim - prim_type = random.choice(["Cube", "Sphere", "Cylinder"]) - _ = prim_utils.create_prim( - f"/World/Objects/Obj_{i:02d}", - prim_type, - translation=position, - scale=(0.25, 0.25, 0.25), - semantic_label=prim_type, - ) - # add rigid properties - SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) - rigid_obj = SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) - # cast to geom prim - geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim) - # set random color - color = Gf.Vec3f(random.random(), random.random(), random.random()) - geom_prim.CreateDisplayColorAttr() - geom_prim.GetDisplayColorAttr().Set([color]) - # Setup camera sensor on the world - cam_prim_path = "/World/CameraSensor" - else: - # Robot - prim_utils.create_prim( - "/World/Robot", - usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_c/anymal_c.usd", - translation=(0.0, 0.0, 0.6), - ) - # Setup camera sensor on the robot - cam_prim_path = "/World/CameraSensor" - - # Create camera - cam_prim = prim_utils.create_prim( - cam_prim_path, - prim_type="Camera", - translation=(5.0, 5.0, 5.0), - orientation=(0.17591988, 0.42470818, 0.82047324, 0.33985113), - ) - _ = UsdGeom.Camera(cam_prim) - # Get render product - render_prod_path = rep.create.render_product(cam_prim_path, resolution=(640, 480)) - # create annotator node - rep_registry = {} - for name in ["rgb", "distance_to_image_plane"]: - # create annotator - rep_annotator = rep.AnnotatorRegistry.get_annotator(name, device="cpu") - rep_annotator.attach(render_prod_path) - # add to registry - rep_registry[name] = rep_annotator - - # Create replicator writer - output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera", args_cli.scenario) - os.makedirs(output_dir, exist_ok=True) - - # Create a view of the stuff we want to see - if args_cli.scenario == "cube": - view: RigidPrim = world.scene.add(RigidPrim("/World/Objects/.*", name="my_object")) - else: - view: Articulation = world.scene.add(Articulation("/World/Robot", name="my_object")) - # Play simulator - world.reset() - # Get initial state - if args_cli.scenario == "cube": - initial_pos, initial_quat = view.get_world_poses() - initial_joint_pos = None - initial_joint_vel = None - else: - initial_pos, initial_quat = view.get_world_poses() - initial_joint_pos = view.get_joint_positions() - initial_joint_vel = view.get_joint_velocities() - - # Counter - count = 0 - prev_im = None - # make episode directory - episode_count = 0 - episode_dir = os.path.join(output_dir, f"episode_{episode_count:06d}") - os.makedirs(episode_dir, exist_ok=True) - # Simulate physics - while simulation_app.is_running(): - # If simulation is stopped, then exit. - if world.is_stopped(): - break - # If simulation is paused, then skip. - if not world.is_playing(): - world.step(render=False) - continue - # Reset on intervals - if count % 25 == 0: - # reset all the state - view.set_world_poses(initial_pos, initial_quat) - if initial_joint_pos is not None: - view.set_joint_positions(initial_joint_pos) - if initial_joint_vel is not None: - view.set_joint_velocities(initial_joint_vel) - # make a new episode directory - episode_dir = os.path.join(output_dir, f"episode_{episode_count:06d}") - os.makedirs(episode_dir, exist_ok=True) - # reset counters - count = 0 - episode_count += 1 - # Step simulation - for _ in range(15): - world.step(render=False) - world.render() - # Update camera data - rgb_data = rep_registry["rgb"].get_data() - depth_data = rep_registry["distance_to_image_plane"].get_data() - - # Show current image number - print(f"[Epi {episode_count:03d}] Current image number: {count:06d}") - # Save data - curr_im = Image.fromarray(rgb_data) - curr_im.save(os.path.join(episode_dir, f"{count:06d}_rgb.png")) - # Save diff - if prev_im is not None: - diff_im = ImageChops.difference(curr_im, prev_im) - # convert to grayscale and threshold - diff_im = diff_im.convert("L") - threshold = 30 - diff_im = diff_im.point(lambda p: p > threshold and 255) - # Save all of them together - dst_im = Image.new("RGB", (curr_im.width + prev_im.width + diff_im.width, diff_im.height)) - dst_im.paste(prev_im, (0, 0)) - dst_im.paste(curr_im, (prev_im.width, 0)) - dst_im.paste(diff_im, (2 * prev_im.width, 0)) - dst_im.save(os.path.join(episode_dir, f"{count:06d}_diff.png")) - - # Save to previous - prev_im = curr_im.copy() - # Update counter - count += 1 - - # Print camera info - print("Received shape of rgb image: ", rgb_data.shape) - print("Received shape of depth image: ", depth_data.shape) - print("-------------------------------") - - -if __name__ == "__main__": - # run the main function - main() - # close sim app - simulation_app.close() diff --git a/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py b/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py index 8798fba361e8..f03012610e97 100644 --- a/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py +++ b/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py @@ -3,205 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""This script demonstrates how to make a floating robot fixed in Isaac Sim.""" - -"""Launch Isaac Sim Simulator first.""" - - -import argparse -import contextlib - -with contextlib.suppress(ModuleNotFoundError): - import isaacsim # noqa: F401 - -from isaacsim import SimulationApp - -# add argparse arguments -parser = argparse.ArgumentParser( - description="This script shows the issue in Isaac Sim with making a floating robot fixed." -) -parser.add_argument("--headless", action="store_true", help="Run in headless mode.") -parser.add_argument("--fix-base", action="store_true", help="Whether to fix the base of the robot.") -# parse the arguments -args_cli = parser.parse_args() - -# launch omniverse app -simulation_app = SimulationApp({"headless": args_cli.headless}) - -"""Rest everything follows.""" - -import logging - -import torch - -import omni.kit.commands -import omni.physx -from isaacsim.core.api.world import World -from isaacsim.core.prims import Articulation -from isaacsim.core.utils.viewports import set_camera_view -from pxr import UsdPhysics - -import isaaclab.sim.utils.nucleus as nucleus_utils -import isaaclab.sim.utils.prims as prim_utils -import isaaclab.sim.utils.stage as stage_utils - -# import logger -logger = logging.getLogger(__name__) - -# check nucleus connection -if nucleus_utils.get_assets_root_path() is None: - msg = ( - "Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n" - "\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus" - ) - logger.error(msg) - raise RuntimeError(msg) - - -ISAAC_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac" -"""Path to the `Isaac` directory on the NVIDIA Nucleus Server.""" - -ISAACLAB_NUCLEUS_DIR = f"{ISAAC_NUCLEUS_DIR}/IsaacLab" -"""Path to the `Isaac/IsaacLab` directory on the NVIDIA Nucleus Server.""" +"""Historic floating-base / fixed-base reproducer (retired). +This script previously depended on Isaac Sim core extensions that Isaac Sim now carries under +``source/deprecated`` in the Isaac Sim repository. It has been retired from Isaac Lab to avoid +depending on those extension IDs and import paths. +Use :class:`~isaaclab.sim.SimulationContext` and ``isaacsim.core.experimental.prims.Articulation`` +for articulation-level debugging. """ -Main -""" - - -def main(): - """Spawns the ANYmal robot and makes it fixed.""" - # Load kit helper - world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu") - # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) - - # Enable hydra scene-graph instancing - # this is needed to visualize the scene when flatcache is enabled - world._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) - - # Spawn things into stage - # Ground-plane - world.scene.add_default_ground_plane(prim_path="/World/defaultGroundPlane", z_position=0.0) - # Lights-1 - prim_utils.create_prim("/World/Light/GreySphere", "SphereLight", translation=(4.5, 3.5, 10.0)) - # Lights-2 - prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0)) - # -- Robot - # resolve asset - usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd" - root_prim_path = "/World/Robot/base" - # add asset - print("Loading robot from: ", usd_path) - prim_utils.create_prim( - "/World/Robot", - usd_path=usd_path, - translation=(0.0, 0.0, 0.6), - ) - # create fixed joint - if args_cli.fix_base: - # get all necessary information - stage = stage_utils.get_current_stage() - root_prim = stage.GetPrimAtPath(root_prim_path) - parent_prim = root_prim.GetParent() - - # here we assume that the root prim is a rigid body - # there is no clear way to deal with situation where the root prim is not a rigid body but has articulation api - # in that case, it is unclear how to get the link to the first link in the tree - if not root_prim.HasAPI(UsdPhysics.RigidBodyAPI): - raise RuntimeError("The root prim does not have the RigidBodyAPI applied.") - - # create fixed joint - omni.kit.commands.execute( - "CreateJointCommand", - stage=stage, - joint_type="Fixed", - from_prim=None, - to_prim=root_prim, - ) - - # move the root to the parent if this is a rigid body - # having a fixed joint on a rigid body makes physx treat it as a part of the maximal coordinate tree - # if we put to joint on the parent, physx parser treats it as a fixed base articulation - # get parent prim - parent_prim = root_prim.GetParent() - # apply api to parent - UsdPhysics.ArticulationRootAPI.Apply(parent_prim) - parent_prim.AddAppliedSchema("PhysxArticulationAPI") - - # copy the attributes - # -- usd attributes - root_usd_articulation_api = UsdPhysics.ArticulationRootAPI(root_prim) - for attr_name in root_usd_articulation_api.GetSchemaAttributeNames(): - attr = root_prim.GetAttribute(attr_name) - parent_prim.GetAttribute(attr_name).Set(attr.Get()) - # -- physx attributes (by name: physxArticulation:*) - for attr in root_prim.GetAttributes(): - name = attr.GetName() - if name.startswith("physxArticulation:"): - parent_prim.GetAttribute(name).Set(attr.Get()) - # remove api from root - root_prim.RemoveAPI(UsdPhysics.ArticulationRootAPI) - root_prim.RemoveAppliedSchema("PhysxArticulationAPI") - - # rename root path to parent path - root_prim_path = parent_prim.GetPath().pathString - - # Setup robot - robot_view = Articulation(root_prim_path, name="ANYMAL") - world.scene.add(robot_view) - # Play the simulator - world.reset() - - # Now we are ready! - print("[INFO]: Setup complete...") - - # dummy actions - # actions = torch.zeros(robot.count, robot.num_actions, device=robot.device) - - init_root_pos_w, init_root_quat_w = robot_view.get_world_poses() - # Define simulation stepping - sim_dt = world.get_physics_dt() - # episode counter - sim_time = 0.0 - count = 0 - # Simulate physics - while simulation_app.is_running(): - # If simulation is stopped, then exit. - if world.is_stopped(): - break - # If simulation is paused, then skip. - if not world.is_playing(): - world.step(render=False) - continue - # do reset - if count % 20 == 0: - # reset - sim_time = 0.0 - count = 0 - # reset root state - root_pos_w = init_root_pos_w.clone() - root_pos_w[:, :2] += torch.rand_like(root_pos_w[:, :2]) * 0.5 - robot_view.set_world_poses(root_pos_w, init_root_quat_w) - # print if it is fixed base - print("Fixed base: ", robot_view._physics_view.shared_metatype.fixed_base) - print("Moving base to: ", root_pos_w[0].cpu().numpy()) - print("-" * 50) - - # apply random joint actions - actions = torch.rand_like(robot_view.get_joint_positions()) * 0.001 - robot_view.set_joint_efforts(actions) - # perform step - world.step() - # update sim-time - sim_time += sim_dt - count += 1 - - -if __name__ == "__main__": - # run the main function - main() - # close sim app - simulation_app.close() +raise RuntimeError( + "This standalone reproducer was retired; it depended on deprecated Isaac Sim core extensions. " + "Use Isaac Lab :mod:`isaaclab.sim` and ``isaacsim.core.experimental.*`` instead." +) diff --git a/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py b/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py index 3e56a441f001..54b13a2f0c1c 100644 --- a/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py +++ b/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py @@ -3,184 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -""" -This script demonstrates how to use the cloner API from Isaac Sim. - -Reference: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/tutorial_gym_cloner.html -""" - -"""Launch Isaac Sim Simulator first.""" - - -import argparse -import contextlib - -with contextlib.suppress(ModuleNotFoundError): - import isaacsim # noqa: F401 - -from isaacsim import SimulationApp - -# add argparse arguments -parser = argparse.ArgumentParser( - description="This script shows the issue in Isaac Sim with GPU simulation of floating robots." -) -parser.add_argument("--num_robots", type=int, default=128, help="Number of robots to spawn.") -parser.add_argument( - "--asset", - type=str, - default="isaaclab", - help="The asset source location for the robot. Can be: isaaclab, oige, custom asset path.", -) -parser.add_argument("--headless", action="store_true", help="Run in headless mode.") -# parse the arguments -args_cli = parser.parse_args() - -# launch omniverse app -simulation_app = SimulationApp({"headless": args_cli.headless}) - -"""Rest everything follows.""" - -import logging -import os - -import torch - -from isaacsim.core.api.world import World -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import Articulation -from isaacsim.core.utils.viewports import set_camera_view - -import isaaclab.sim.utils.nucleus as nucleus_utils -import isaaclab.sim.utils.prims as prim_utils - -# import logger -logger = logging.getLogger(__name__) +"""Historic legged-robot cloning reproducer (retired). -# check nucleus connection -if nucleus_utils.get_assets_root_path() is None: - msg = ( - "Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n" - "\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus" - ) - logger.error(msg) - raise RuntimeError(msg) +This script previously depended on Isaac Sim core extensions that Isaac Sim now carries under +``source/deprecated`` in the Isaac Sim repository. It has been retired from Isaac Lab to avoid +depending on those extension IDs and import paths. - -ISAAC_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac" -"""Path to the `Isaac` directory on the NVIDIA Nucleus Server.""" - -ISAACLAB_NUCLEUS_DIR = f"{ISAAC_NUCLEUS_DIR}/IsaacLab" -"""Path to the `Isaac/IsaacLab` directory on the NVIDIA Nucleus Server.""" - - -""" -Main +Use :class:`~isaaclab.sim.SimulationContext`, :class:`isaacsim.core.cloner.GridCloner`, and +``isaacsim.core.experimental.prims.Articulation`` for cloning workflows. """ - -def main(): - """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" - - # Load kit helper - world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0") - # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) - - # Enable hydra scene-graph instancing - # this is needed to visualize the scene when flatcache is enabled - world._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) - - # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=world.stage) - cloner.define_base_env("/World/envs") - # Everything under the namespace "/World/envs/env_0" will be cloned - prim_utils.define_prim("/World/envs/env_0") - - # Spawn things into stage - # Ground-plane - world.scene.add_default_ground_plane(prim_path="/World/defaultGroundPlane", z_position=0.0) - # Lights-1 - prim_utils.create_prim("/World/Light/GreySphere", "SphereLight", translation=(4.5, 3.5, 10.0)) - # Lights-2 - prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0)) - # -- Robot - # resolve asset - if args_cli.asset == "isaaclab": - usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd" - root_prim_path = "/World/envs/env_.*/Robot/base" - elif args_cli.asset == "oige": - usd_path = f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_c/anymal_c.usd" - root_prim_path = "/World/envs/env_.*/Robot" - elif os.path.exists(args_cli.asset): - usd_path = args_cli.asset - else: - raise ValueError(f"Invalid asset: {args_cli.asset}. Must be one of: isaaclab, oige.") - # add asset - print("Loading robot from: ", usd_path) - prim_utils.create_prim( - "/World/envs/env_0/Robot", - usd_path=usd_path, - translation=(0.0, 0.0, 0.6), - ) - - # Clone the scene - num_envs = args_cli.num_robots - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) - envs_positions = cloner.clone( - source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True - ) - # convert environment positions to torch tensor - envs_positions = torch.tensor(envs_positions, dtype=torch.float, device=world.device) - # filter collisions within each environment instance - physics_scene_path = world.get_physics_context().prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", envs_prim_paths, global_paths=["/World/defaultGroundPlane"] - ) - - # Resolve robot prim paths - if args_cli.asset == "isaaclab": - root_prim_path = "/World/envs/env_.*/Robot/base" - elif args_cli.asset == "oige": - root_prim_path = "/World/envs/env_.*/Robot" - elif os.path.exists(args_cli.asset): - usd_path = args_cli.asset - root_prim_path = "/World/envs/env_.*/Robot" - else: - raise ValueError(f"Invalid asset: {args_cli.asset}. Must be one of: isaaclab, oige.") - # Setup robot - robot_view = Articulation(root_prim_path, name="ANYMAL") - world.scene.add(robot_view) - # Play the simulator - world.reset() - - # Now we are ready! - print("[INFO]: Setup complete...") - - # dummy actions - # actions = torch.zeros(robot.count, robot.num_actions, device=robot.device) - - # Define simulation stepping - sim_dt = world.get_physics_dt() - # episode counter - sim_time = 0.0 - # Simulate physics - while simulation_app.is_running(): - # If simulation is stopped, then exit. - if world.is_stopped(): - break - # If simulation is paused, then skip. - if not world.is_playing(): - world.step(render=False) - continue - # perform step - world.step() - # update sim-time - sim_time += sim_dt - - -if __name__ == "__main__": - # run the main function - main() - # close sim app - simulation_app.close() +raise RuntimeError( + "This standalone reproducer was retired; it depended on deprecated Isaac Sim core extensions. " + "Use Isaac Lab :mod:`isaaclab.sim` and ``isaacsim.core.experimental.*`` instead." +) diff --git a/source/isaaclab/test/deps/isaacsim/check_ref_count.py b/source/isaaclab/test/deps/isaacsim/check_ref_count.py index c0380183a28c..02465f722f3d 100644 --- a/source/isaaclab/test/deps/isaacsim/check_ref_count.py +++ b/source/isaaclab/test/deps/isaacsim/check_ref_count.py @@ -20,7 +20,6 @@ """Launch Isaac Sim Simulator first.""" - import contextlib with contextlib.suppress(ModuleNotFoundError): @@ -39,11 +38,12 @@ import torch # noqa: F401 -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.prims import Articulation +import carb +from isaacsim.core.experimental.prims import Articulation import isaaclab.sim.utils.nucleus as nucleus_utils import isaaclab.sim.utils.prims as prim_utils +from isaaclab.sim import SimulationCfg, SimulationContext # import logger logger = logging.getLogger(__name__) @@ -85,17 +85,13 @@ def __init__(self): # Resolve robot prim paths root_prim_path = "/World/Robot/base" # Setup robot - self.view = Articulation(root_prim_path, name="ANYMAL") + self.view = Articulation(root_prim_path) def __del__(self): """Delete the Anymal articulation class.""" print("Deleting the Anymal view.") self.view = None - def initialize(self): - """Initialize the Anymal view.""" - self.view.initialize() - """ Main @@ -105,12 +101,10 @@ def initialize(self): def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" - # Load kit helper - sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0") + carb.settings.get_settings().set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) - # Enable hydra scene-graph instancing - # this is needed to visualize the scene when flatcache is enabled - sim._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) + # Load kit helper + sim = SimulationContext(cfg=SimulationCfg(dt=0.005, device="cuda:0")) # Create a dummy tensor for testing # Uncommenting the following line will yield a reference count of 1 for the robot (as desired) @@ -130,8 +124,6 @@ def main(): print("Referrers of the robot view: ", gc.get_referrers(robot)) print("---" * 10) - robot.initialize() - print("Reference count of the robot view: ", ctypes.c_long.from_address(id(robot)).value) print("Referrers of the robot view: ", gc.get_referrers(robot)) print("---" * 10) @@ -144,7 +136,7 @@ def main(): print("---" * 10) # Clean up - sim.clear_instance() + SimulationContext.clear_instance() print("Reference count of the robot view: ", ctypes.c_long.from_address(id(robot)).value) print("Referrers of the robot view: ", gc.get_referrers(robot)) diff --git a/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py b/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py index 99d7d452ef79..dd3875994e38 100644 --- a/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py +++ b/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py @@ -3,163 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -""" -This script shows how to use replicator to randomly change the textures of a USD scene. - -Note: - Currently this script fails since cloner does not support changing textures of cloned - USD prims. This is because the prims are cloned using `Sdf.ChangeBlock` which does not - allow individual texture changes. - -Usage: - -.. code-block:: bash +"""Historic replicator texture randomization reproducer (retired). - ./isaaclab.sh -p source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py +This script previously depended on Isaac Sim core extensions that Isaac Sim now carries under +``source/deprecated`` in the Isaac Sim repository. It has been retired from Isaac Lab to avoid +depending on those extension IDs and import paths. +Use :class:`~isaaclab.sim.SimulationContext`, :class:`isaacsim.core.cloner.GridCloner`, and +``isaacsim.core.experimental.*`` when experimenting with Omniverse Replicator workflows. """ -"""Launch Isaac Sim Simulator first.""" - -import argparse - -# isaaclab -from isaaclab.app import AppLauncher - -# add argparse arguments -parser = argparse.ArgumentParser( - description="This script shows how to use replicator to randomly change the textures of a USD scene." +raise RuntimeError( + "This standalone reproducer was retired; it depended on deprecated Isaac Sim core extensions. " + "Use Isaac Lab :mod:`isaaclab.sim` and ``isaacsim.core.experimental.*`` instead." ) -# append AppLauncher cli args -AppLauncher.add_app_launcher_args(parser) -# 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 omni.replicator.core as rep -from isaacsim.core.api.objects import DynamicSphere -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import RigidPrim -from isaacsim.core.utils.viewports import set_camera_view - -import isaaclab.sim.utils.prims as prim_utils - - -def main(): - """Spawn a bunch of balls and randomly change their textures.""" - - # Load kit helper - sim_params = { - "use_gpu": True, - "use_gpu_pipeline": True, - "use_flatcache": True, # deprecated from Isaac Sim 2023.1 onwards - "use_fabric": True, # used from Isaac Sim 2023.1 onwards - "enable_scene_query_support": True, - } - sim = SimulationContext( - physics_dt=1.0 / 60.0, rendering_dt=1.0 / 60.0, sim_params=sim_params, backend="torch", device="cuda:0" - ) - # Set main camera - set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) - - # Parameters - num_balls = 128 - - # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=sim.stage) - cloner.define_base_env("/World/envs") - # Everything under the namespace "/World/envs/env_0" will be cloned - prim_utils.define_prim("/World/envs/env_0") - - # Define the scene - # -- Ball - DynamicSphere(prim_path="/World/envs/env_0/ball", translation=np.array([0.0, 0.0, 5.0]), mass=0.5, radius=0.25) - - # Clone the scene - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_balls) - env_positions = cloner.clone( - source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True, copy_from_source=True - ) - physics_scene_path = sim.get_physics_context().prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] - ) - - # Use replicator to randomize color on the spheres - with rep.new_layer(): - # Define a function to get all the shapes - def get_shapes(): - shapes = rep.get.prims(path_pattern="/World/envs/env_.*/ball") - with shapes: - rep.randomizer.color(colors=rep.distribution.uniform((0, 0, 0), (1, 1, 1))) - return shapes.node - - # Register the function - rep.randomizer.register(get_shapes) - # Specify the frequency of randomization - with rep.trigger.on_frame(): - rep.randomizer.get_shapes() - - # Set ball positions over terrain origins - # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) - # cache initial state of the balls - ball_initial_positions = torch.tensor(env_positions, dtype=torch.float, device=sim.device) - ball_initial_positions[:, 2] += 5.0 - # set initial poses - # note: setting here writes to USD :) - ball_view.set_world_poses(positions=ball_initial_positions) - - # Play simulator - sim.reset() - # Step replicator to randomize colors - rep.orchestrator.step(pause_timeline=False) - # Stop replicator to prevent further randomization - rep.orchestrator.stop() - # Pause simulator at the beginning for inspection - sim.pause() - - # Initialize the ball views for physics simulation - ball_view.initialize() - ball_initial_velocities = ball_view.get_velocities() - - # Create a counter for resetting the scene - step_count = 0 - # Simulate physics - while simulation_app.is_running(): - # If simulation is stopped, then exit. - if sim.is_stopped(): - break - # If simulation is paused, then skip. - if not sim.is_playing(): - sim.step() - continue - # Reset the scene - if step_count % 500 == 0: - # reset the balls - ball_view.set_world_poses(positions=ball_initial_positions) - ball_view.set_velocities(ball_initial_velocities) - # reset the counter - step_count = 0 - # Step simulation - sim.step() - # Update counter - step_count += 1 - - -if __name__ == "__main__": - # run the main function - main() - # close sim app - simulation_app.close() diff --git a/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py b/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py index b2db866a575b..2a6157120848 100644 --- a/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py +++ b/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py @@ -16,7 +16,7 @@ """Rest everything follows.""" -from isaacsim.core.utils.extensions import enable_extension +from isaacsim.core.experimental.utils.app import enable_extension import isaaclab.sim as sim_utils from isaaclab.envs import ManagerBasedRLEnv, ManagerBasedRLEnvCfg diff --git a/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py b/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py index 4824d968284f..2ffd89edf2f4 100644 --- a/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py +++ b/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py @@ -46,10 +46,9 @@ import torch -from isaacsim.core.cloner import GridCloner - import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen +from isaaclab import cloner as lab_cloner from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.sensors.ray_caster import MultiMeshRayCaster, MultiMeshRayCasterCfg, patterns from isaaclab.sim import SimulationCfg, SimulationContext @@ -63,8 +62,10 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): """Design the scene.""" # Create interface to clone the scene - cloner = GridCloner(spacing=10.0, stage=sim.stage) - cloner.define_base_env("/World/envs") + # Create environment clones using Lab's cloner utilities + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_envs, dtype=torch.long, device=sim.device) + env_origins, _ = lab_cloner.grid_transforms(num_envs, spacing=10.0, device=sim.device) # Everything under the namespace "/World/envs/env_0" will be cloned sim.stage.DefinePrim("/World/envs/env_0", "Xform") # Define the scene @@ -99,12 +100,11 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): ) # Clone the scene - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) - cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) + envs_prim_paths = [f"/World/envs/env_{i}" for i in range(num_envs)] + lab_cloner.usd_replicate(sim.stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) physics_scene_path = sim.get_physics_context().prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] + lab_cloner.filter_collisions( + sim.stage, physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) diff --git a/source/isaaclab/test/sensors/check_ray_caster.py b/source/isaaclab/test/sensors/check_ray_caster.py index 5e1e88472ae5..dc815afc1464 100644 --- a/source/isaaclab/test/sensors/check_ray_caster.py +++ b/source/isaaclab/test/sensors/check_ray_caster.py @@ -41,10 +41,9 @@ import torch -from isaacsim.core.cloner import GridCloner - import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen +from isaaclab import cloner as lab_cloner from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.sensors.ray_caster import RayCaster, RayCasterCfg, patterns from isaaclab.sim import SimulationCfg, SimulationContext @@ -57,8 +56,10 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): """Design the scene.""" # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=sim.stage) - cloner.define_base_env("/World/envs") + # Create environment clones using Lab's cloner utilities + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_envs, dtype=torch.long, device=sim.device) + env_origins, _ = lab_cloner.grid_transforms(num_envs, spacing=2.0, device=sim.device) # Everything under the namespace "/World/envs/env_0" will be cloned sim.stage.DefinePrim("/World/envs/env_0", "Xform") # Define the scene @@ -75,12 +76,11 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): ) cfg.func("/World/envs/env_0/ball", cfg, translation=(0.0, 0.0, 5.0)) # Clone the scene - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) - cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) + envs_prim_paths = [f"/World/envs/env_{i}" for i in range(num_envs)] + lab_cloner.usd_replicate(sim.stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) physics_scene_path = sim.get_physics_context().prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] + lab_cloner.filter_collisions( + sim.stage, physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index e927d2572756..e05fd0deb550 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -16,7 +16,7 @@ import pytest -from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name +from isaacsim.core.experimental.utils.app import enable_extension, get_extension_path import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -35,7 +35,7 @@ def test_setup_teardown(): # Setup: Create MJCF config enable_extension("isaacsim.asset.importer.mjcf") - extension_path = get_extension_path_from_name("isaacsim.asset.importer.mjcf") + extension_path = get_extension_path("isaacsim.asset.importer.mjcf") config = MjcfConverterCfg( asset_path=f"{extension_path}/data/mjcf/nv_ant.xml", self_collision=False, diff --git a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py index ebe8158750fe..1add70c70989 100644 --- a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py @@ -17,13 +17,14 @@ import pytest +import torch import omni.physx import omni.usd import usdrt -from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils +from isaaclab import cloner from isaaclab.sim.simulation_context import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR from isaaclab.utils.version import get_isaac_sim_version @@ -194,23 +195,19 @@ def test_stage_in_memory_with_clone_in_fabric(sim): base_env_path = "/World/envs" source_prim_path = f"{base_env_path}/env_0" - # create cloner - cloner = GridCloner(spacing=3, stage=stage_in_memory) - cloner.define_base_env(base_env_path) + # create environment clones using Isaac Lab's cloner utilities + env_ids = torch.arange(num_clones, dtype=torch.long, device="cpu") + env_origins, _ = cloner.grid_transforms(num_clones, spacing=3.0, device="cpu") # create source prim + stage_in_memory.DefinePrim(source_prim_path, "Xform") sim_utils.create_prim(f"{source_prim_path}/Robot", "Xform", usd_path=usd_path) # generate target paths - target_paths = cloner.generate_paths("/World/envs/env", num_clones) + env_fmt = "/World/envs/env_{}" # clone robots at target paths - cloner.clone( - source_prim_path=source_prim_path, - base_env_path=base_env_path, - prim_paths=target_paths, - replicate_physics=True, - ) + cloner.usd_replicate(stage_in_memory, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) # verify prims exist in fabric stage using usdrt apis stage_id = sim_utils.get_current_stage_id() diff --git a/source/isaaclab/test/sim/test_views_xform_prim.py b/source/isaaclab/test/sim/test_views_xform_prim.py index 2b40705f732a..ff9eef7a33f4 100644 --- a/source/isaaclab/test/sim/test_views_xform_prim.py +++ b/source/isaaclab/test/sim/test_views_xform_prim.py @@ -21,7 +21,7 @@ from pxr import Gf, UsdGeom # noqa: E402 try: - from isaacsim.core.prims import XFormPrim as _IsaacSimXformPrimView + from isaacsim.core.experimental.prims import XformPrim as _IsaacSimXformPrimView except (ModuleNotFoundError, ImportError): _IsaacSimXformPrimView = None diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index c024d33bb5f1..a8229023f90c 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -64,10 +64,9 @@ import torch -from isaacsim.core.cloner import GridCloner - import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen +from isaaclab import cloner as lab_cloner from isaaclab.sim import SimulationCfg, SimulationContext from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG from isaaclab.terrains.terrain_importer import TerrainImporter @@ -86,8 +85,10 @@ def main(): num_balls = 2048 # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=sim.stage) - cloner.define_base_env("/World/envs") + # Create environment clones using Lab's cloner utilities + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_balls, dtype=torch.long, device=sim.device) + env_origins, _ = lab_cloner.grid_transforms(num_balls, spacing=2.0, device=sim.device) # Everything under the namespace "/World/envs/env_0" will be cloned sim_utils.define_prim("/World/envs/env_0") @@ -145,12 +146,11 @@ def main(): mesh_sphere_cfg.func(ball_prim_path, mesh_sphere_cfg, translation=(0.0, 0.0, 0.5)) # Clone the scene - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_balls) - cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) + envs_prim_paths = [f"/World/envs/env_{i}" for i in range(num_balls)] + lab_cloner.usd_replicate(sim.stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) physics_scene_path = sim.cfg.physics.physics_prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] + lab_cloner.filter_collisions( + sim.stage, physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) # Set ball positions over terrain origins using FrameView (before simulation starts) diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index 8842c6df673b..5234df4cae51 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -20,11 +20,11 @@ import trimesh import warp as wp -from isaacsim.core.cloner import GridCloner -from pxr import Usd, UsdGeom +from pxr import UsdGeom import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen +from isaaclab import cloner as lab_cloner from isaaclab.sim import PreviewSurfaceCfg, SimulationContext, build_simulation_context, get_first_matching_child_prim from isaaclab.terrains import TerrainImporter, TerrainImporterCfg from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG @@ -34,8 +34,8 @@ @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("env_spacing", [1.0, 4.325, 8.0]) @pytest.mark.parametrize("num_envs", [1, 4, 125, 379, 1024]) -def test_grid_clone_env_origins(device, env_spacing, num_envs): - """Tests that env origins are consistent when computed using the TerrainImporter and IsaacSim GridCloner.""" +def test_terrain_importer_env_origins(device, env_spacing, num_envs): + """Tests that env origins are consistent when computed using the TerrainImporter and Lab's grid_transforms.""" with build_simulation_context(device=device, auto_add_lighting=True) as sim: sim._app_control_on_stop_handle = None # create terrain importer @@ -50,11 +50,11 @@ def test_grid_clone_env_origins(device, env_spacing, num_envs): # obtain env origins using terrain importer terrain_importer_origins = terrain_importer.env_origins - # obtain env origins using grid cloner - grid_cloner_origins = _obtain_grid_cloner_env_origins(num_envs, env_spacing, stage=sim.stage, device=sim.device) + # obtain env origins using Lab's grid_transforms + lab_grid_origins, _ = lab_cloner.grid_transforms(num_envs, spacing=env_spacing, device=sim.device) # check if the env origins are the same - torch.testing.assert_close(terrain_importer_origins, grid_cloner_origins, rtol=1e-5, atol=1e-5) + torch.testing.assert_close(terrain_importer_origins, lab_grid_origins, rtol=1e-5, atol=1e-5) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @@ -240,20 +240,6 @@ def _obtain_collision_mesh(mesh_prim_path: str, mesh_type: Literal["Mesh", "Plan return None -def _obtain_grid_cloner_env_origins(num_envs: int, env_spacing: float, stage: Usd.Stage, device: str) -> torch.Tensor: - """Obtain the env origins generated by IsaacSim GridCloner (grid_cloner.py).""" - # create grid cloner - cloner = GridCloner(spacing=env_spacing, stage=stage) - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) - # create source prim - stage.DefinePrim("/World/envs/env_0", "Xform") - # clone envs using grid cloner - env_origins = cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) - # return as tensor - return torch.tensor(env_origins, dtype=torch.float32, device=device) - - def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: bool = False): """Create a scene with terrain and randomly spawned balls. @@ -270,9 +256,10 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: ) terrain_importer = TerrainImporter(terrain_importer_cfg) - # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=sim.stage) - cloner.define_base_env("/World/envs") + # Create environment clones using Lab's cloner utilities + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_balls, dtype=torch.long, device=sim.device) + env_origins, _ = lab_cloner.grid_transforms(num_balls, spacing=2.0, device=sim.device) # Everything under the namespace "/World/envs/env_0" will be cloned sim.stage.DefinePrim("/World/envs/env_0", "Xform") @@ -314,16 +301,11 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: mesh_sphere_cfg.func(ball_prim_path, mesh_sphere_cfg, translation=(0.0, 0.0, 0.5)) # Clone the scene - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_balls) - cloner.clone( - source_prim_path="/World/envs/env_0", - prim_paths=envs_prim_paths, - replicate_physics=True, - ) + envs_prim_paths = [f"/World/envs/env_{i}" for i in range(num_balls)] + lab_cloner.usd_replicate(sim.stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) physics_scene_path = sim.cfg.physics_prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] + lab_cloner.filter_collisions( + sim.stage, physics_scene_path, "/World/collisions", prim_paths=envs_prim_paths, global_paths=["/World/ground"] ) # Set ball positions over terrain origins diff --git a/source/isaaclab_mimic/config/extension.toml b/source/isaaclab_mimic/config/extension.toml index 6ac398658874..f53461c3fc6f 100644 --- a/source/isaaclab_mimic/config/extension.toml +++ b/source/isaaclab_mimic/config/extension.toml @@ -1,7 +1,7 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "1.2.4" +version = "1.2.5" # Description category = "isaaclab" diff --git a/source/isaaclab_mimic/docs/CHANGELOG.rst b/source/isaaclab_mimic/docs/CHANGELOG.rst index 65659942492f..782cf6f7d220 100644 --- a/source/isaaclab_mimic/docs/CHANGELOG.rst +++ b/source/isaaclab_mimic/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +1.2.5 (2026-04-14) +~~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Updated mobility path utilities to import from ``isaacsim.replicator.experimental.mobility_gen``. + + 1.2.4 (2026-04-06) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py index 3baacc3dfb31..46ade12e70a6 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py +++ b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py @@ -6,7 +6,7 @@ import torch -from isaacsim.replicator.mobility_gen.impl.path_planner import compress_path, generate_paths +from isaacsim.replicator.experimental.mobility_gen.impl.path_planner import compress_path, generate_paths from .occupancy_map_utils import OccupancyMap from .scene_utils import HasPose2d diff --git a/source/isaaclab_physx/benchmark/assets/benchmark_articulation.py b/source/isaaclab_physx/benchmark/assets/benchmark_articulation.py index 190d9e7ee165..9b2620022b51 100644 --- a/source/isaaclab_physx/benchmark/assets/benchmark_articulation.py +++ b/source/isaaclab_physx/benchmark/assets/benchmark_articulation.py @@ -63,7 +63,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) import warp as wp diff --git a/source/isaaclab_physx/benchmark/assets/benchmark_articulation_data.py b/source/isaaclab_physx/benchmark/assets/benchmark_articulation_data.py index 3cdca6665a86..5778f16017bc 100644 --- a/source/isaaclab_physx/benchmark/assets/benchmark_articulation_data.py +++ b/source/isaaclab_physx/benchmark/assets/benchmark_articulation_data.py @@ -60,7 +60,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object.py b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object.py index c4411325d223..eaadfe31f0a9 100644 --- a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object.py +++ b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object.py @@ -61,7 +61,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection.py b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection.py index a244d3b52cae..2617be3d2667 100644 --- a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection.py +++ b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection.py @@ -56,7 +56,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection_data.py b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection_data.py index 1506c9443af8..0b0327e9bf3c 100644 --- a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection_data.py +++ b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_collection_data.py @@ -59,7 +59,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_data.py b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_data.py index acd413e84704..9c0d65da2da3 100644 --- a/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_data.py +++ b/source/isaaclab_physx/benchmark/assets/benchmark_rigid_object_data.py @@ -57,7 +57,7 @@ _mock_physics_sim_view = MagicMock() _mock_physics_sim_view.get_gravity.return_value = (0.0, 0.0, -9.81) -from isaacsim.core.simulation_manager import SimulationManager +from isaaclab_physx.physics import PhysxManager as SimulationManager SimulationManager.get_physics_sim_view = MagicMock(return_value=_mock_physics_sim_view) diff --git a/source/isaaclab_physx/docs/CHANGELOG.rst b/source/isaaclab_physx/docs/CHANGELOG.rst index 6f9bcbe733f6..be7e0184817b 100644 --- a/source/isaaclab_physx/docs/CHANGELOG.rst +++ b/source/isaaclab_physx/docs/CHANGELOG.rst @@ -15,6 +15,14 @@ Fixed be constructed without a running Kit instance (regression caught by ``test_env_cfg_no_forbidden_imports``). +Changed +^^^^^^^ + +* Migrated :func:`~isaaclab_physx.renderers.kit_viewport_utils.set_kit_renderer_camera_view` + off the deprecated ``isaacsim.core.utils.viewports.set_camera_view`` to + ``isaacsim.core.rendering_manager.ViewportManager.set_camera_view``, matching the + pattern used by the Kit perspective video helper. + 0.5.24 (2026-04-22) ~~~~~~~~~~~~~~~~~~~ @@ -25,6 +33,12 @@ Changed * Updated imports of the PhysX tensors API from ``omni.physics.tensors.impl.api`` to ``omni.physics.tensors.api`` to track the upstream Isaac Sim module relocation (the ``impl`` submodule was removed). +* Migrated the PhysX scene data provider, PhysX asset micro-benchmarks, and cross-backend asset + interface tests off ``isaacsim.core.simulation_manager.SimulationManager`` to + :class:`~isaaclab_physx.physics.PhysxManager` (imported as ``SimulationManager`` to mirror the + Newton backend's ``NewtonManager as SimulationManager`` convention). +* Updated optional-extension enablement and Kit perspective capture helpers to use non-deprecated + Isaac Sim module paths (``isaacsim.core.experimental.utils.app`` and ``isaacsim.core.rendering_manager``). 0.5.23 (2026-04-23) @@ -101,7 +115,6 @@ Fixed the artifact, per-environment, and filtered Newton models in :class:`~isaaclab_physx.scene_data_providers.PhysxSceneDataProvider`. - 0.5.18 (2026-04-16) ~~~~~~~~~~~~~~~~~~~ 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 cd1e4e0aaea9..590289feb659 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 @@ -13,7 +13,7 @@ import torch import warp as wp -from isaacsim.core.utils.extensions import enable_extension +from isaacsim.core.experimental.utils.app import enable_extension import isaaclab.sim as sim_utils from isaaclab.assets import AssetBase diff --git a/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py b/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py index af421a032399..f371aac7c603 100644 --- a/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py +++ b/source/isaaclab_physx/isaaclab_physx/renderers/kit_viewport_utils.py @@ -26,9 +26,13 @@ def set_kit_renderer_camera_view( This does not broadcast to visualizers. """ try: - import isaacsim.core.utils.viewports as isaacsim_viewports + from isaacsim.core.rendering_manager import ViewportManager - isaacsim_viewports.set_camera_view(eye=list(eye), target=list(target), camera_prim_path=str(camera_prim_path)) + ViewportManager.set_camera_view( + str(camera_prim_path), + eye=list(eye), + target=list(target), + ) except (ImportError, ModuleNotFoundError) as exc: logger.debug("[kit_viewport] Renderer camera update skipped (no Kit): %s", exc) except Exception as exc: diff --git a/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py b/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py index 1636c8b5a650..fde9402c5f2e 100644 --- a/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py +++ b/source/isaaclab_physx/isaaclab_physx/scene_data_providers/physx_scene_data_provider.py @@ -80,7 +80,7 @@ def __init__(self, stage, simulation_context) -> None: stage: USD stage handle. simulation_context: Active simulation context. """ - from isaacsim.core.simulation_manager import SimulationManager + from isaaclab_physx.physics import PhysxManager as SimulationManager self._simulation_context = simulation_context self._stage = stage diff --git a/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py b/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py index 300898ab765d..16f7046dbe97 100644 --- a/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab_physx/isaaclab_physx/sensors/contact_sensor/contact_sensor.py @@ -65,7 +65,7 @@ class ContactSensor(BaseContactSensor): it against the object. .. _PhysX ContactReporter: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_contact_report_a_p_i.html - .. _RigidContact: https://docs.isaacsim.omniverse.nvidia.com/latest/py/source/extensions/isaacsim.core.api/docs/index.html#isaacsim.core.api.sensors.RigidContactView + .. _RigidContact: https://docs.isaacsim.omniverse.nvidia.com/latest/py/source/extensions/isaacsim.core.experimental.prims/docs/index.html """ cfg: ContactSensorCfg diff --git a/source/isaaclab_physx/isaaclab_physx/video_recording/isaacsim_kit_perspective_video.py b/source/isaaclab_physx/isaaclab_physx/video_recording/isaacsim_kit_perspective_video.py index 769d87251886..ba844f03380d 100644 --- a/source/isaaclab_physx/isaaclab_physx/video_recording/isaacsim_kit_perspective_video.py +++ b/source/isaaclab_physx/isaaclab_physx/video_recording/isaacsim_kit_perspective_video.py @@ -32,12 +32,12 @@ def render_rgb_array(self) -> np.ndarray: h, w = self.cfg.window_height, self.cfg.window_width if self._rgb_annotator is None: - import isaacsim.core.utils.viewports as isaacsim_viewports + from isaacsim.core.rendering_manager import ViewportManager - isaacsim_viewports.set_camera_view( + ViewportManager.set_camera_view( + self.cfg.camera_prim_path, eye=list(self.cfg.camera_position), target=list(self.cfg.camera_target), - camera_prim_path=self.cfg.camera_prim_path, ) self._render_product = rep.create.render_product(self.cfg.camera_prim_path, (w, h)) self._rgb_annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu") diff --git a/source/isaaclab_physx/test/sensors/check_contact_sensor.py b/source/isaaclab_physx/test/sensors/check_contact_sensor.py index 035518fdf4d3..e840f00f1d34 100644 --- a/source/isaaclab_physx/test/sensors/check_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_contact_sensor.py @@ -36,9 +36,8 @@ import torch -from isaacsim.core.cloner import GridCloner - import isaaclab.sim as sim_utils +from isaaclab import cloner as lab_cloner from isaaclab.assets import Articulation from isaaclab.sensors.contact_sensor import ContactSensor, ContactSensorCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -82,16 +81,16 @@ def main(): # this is needed to visualize the scene when flatcache is enabled sim._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) - # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=sim.stage) - cloner.define_base_env("/World/envs") + # Create environment clones using Lab's cloner utilities + num_envs = args_cli.num_robots + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_envs, dtype=torch.long, device=sim.device) + env_origins, _ = lab_cloner.grid_transforms(num_envs, spacing=2.0, device=sim.device) # Everything under the namespace "/World/envs/env_0" will be cloned sim.stage.DefinePrim("/World/envs/env_0", "Xform") # Clone the scene - num_envs = args_cli.num_robots - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) - _ = cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) + envs_prim_paths = [f"/World/envs/env_{i}" for i in range(num_envs)] + lab_cloner.usd_replicate(sim.stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) # Design props design_scene() # Spawn things into the scene @@ -110,8 +109,8 @@ def main(): contact_sensor = ContactSensor(cfg=contact_sensor_cfg) # filter collisions within each environment instance physics_scene_path = sim.get_physics_context().prim_path - cloner.filter_collisions( - physics_scene_path, "/World/collisions", envs_prim_paths, global_paths=["/World/defaultGroundPlane"] + lab_cloner.filter_collisions( + sim.stage, physics_scene_path, "/World/collisions", envs_prim_paths, global_paths=["/World/defaultGroundPlane"] ) # Play the simulator diff --git a/source/isaaclab_physx/test/sensors/check_pva_sensor.py b/source/isaaclab_physx/test/sensors/check_pva_sensor.py index a7672d3fa3d1..75bc64673df3 100644 --- a/source/isaaclab_physx/test/sensors/check_pva_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_pva_sensor.py @@ -40,11 +40,11 @@ import torch -from isaacsim.core.cloner import GridCloner -from isaacsim.core.utils.viewports import set_camera_view +from isaacsim.core.rendering_manager import ViewportManager import isaaclab.sim as sim_utils import isaaclab.terrains as terrain_gen +from isaaclab import cloner as lab_cloner from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.sensors.pva import Pva, PvaCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -72,13 +72,15 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048) -> RigidObject: # obtain the current stage stage = sim_utils.get_current_stage() # Create interface to clone the scene - cloner = GridCloner(spacing=2.0, stage=stage) - cloner.define_base_env("/World/envs") - envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) + # Create environment clones using Lab's cloner utilities + env_fmt = "/World/envs/env_{}" + env_ids = torch.arange(num_envs, dtype=torch.long, device=sim.device) + env_origins, _ = lab_cloner.grid_transforms(num_envs, spacing=2.0, device=sim.device) + envs_prim_paths = [f"/World/envs/env_{i}" for i in range(num_envs)] # create source prim stage.DefinePrim(envs_prim_paths[0], "Xform") # clone the env xform - cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True) + lab_cloner.usd_replicate(stage, [env_fmt.format(0)], [env_fmt], env_ids, positions=env_origins) # Define the scene # -- Light cfg = sim_utils.DistantLightCfg(intensity=2000) @@ -105,7 +107,8 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048) -> RigidObject: logging.info(f"Physics scene prim path: {physics_scene_prim_path}") break # filter collisions within each environment instance - cloner.filter_collisions( + lab_cloner.filter_collisions( + stage, physics_scene_prim_path, "/World/collisions", envs_prim_paths, @@ -119,7 +122,7 @@ def main(): # Load kit helper sim = SimulationContext(SimulationCfg()) # Set main camera - set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) + ViewportManager.set_camera_view("/OmniverseKit_Persp", eye=[0.0, 30.0, 25.0], target=[0.0, 0.0, -2.5]) # Parameters num_envs = args_cli.num_envs diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index c1c79a9b1e22..e5bc109230fc 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 = "1.5.26" +version = "1.5.27" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 8124ac3c4ab3..005ac61984cf 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +1.5.27 (2026-04-25) +~~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Updated stack-event utilities to enable optional extensions via + ``isaacsim.core.experimental.utils.app.enable_extension`` (non-deprecated Isaac Sim path). + + 1.5.26 (2026-04-25) ~~~~~~~~~~~~~~~~~~~ @@ -61,7 +71,6 @@ Fixed * Refreshed Newton Warp renderer golden images in ``test_rendering_correctness`` so image baselines match the current camera output after Newton shape color alignment and the clear background color change. - 1.5.21 (2026-04-13) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py index ada7f2fc259c..9232656eb2a6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py @@ -296,7 +296,7 @@ def randomize_visual_texture_material( # textures = [default_texture] # enable replicator extension if not already enabled - from isaacsim.core.utils.extensions import enable_extension + from isaacsim.core.experimental.utils.app import enable_extension enable_extension("omni.replicator.core") # we import the module here since we may not always need the replicator diff --git a/source/isaaclab_tasks/test/env_test_utils.py b/source/isaaclab_tasks/test/env_test_utils.py index 6de1c6acaa52..f152f8bab961 100644 --- a/source/isaaclab_tasks/test/env_test_utils.py +++ b/source/isaaclab_tasks/test/env_test_utils.py @@ -26,9 +26,7 @@ # Map of task IDs to the reason for marking the corresponding parametrized # test cases as expected failures. Tests that consume :func:`setup_environment` # automatically pick up these marks via :class:`pytest.param`. -XFAIL_TASKS: dict[str, str] = { - "Isaac-Cartpole-RGB-TheiaTiny-v0": "TheiaTiny environment is currently broken; xfailed pending fix.", -} +XFAIL_TASKS: dict[str, str] = {} def _is_teleop_env(task_spec) -> bool: diff --git a/source/isaaclab_tasks/test/test_rendering_correctness.py b/source/isaaclab_tasks/test/test_rendering_correctness.py index b87371e3a300..26caae812808 100644 --- a/source/isaaclab_tasks/test/test_rendering_correctness.py +++ b/source/isaaclab_tasks/test/test_rendering_correctness.py @@ -809,16 +809,23 @@ def test_cartpole(cartpole_env): # --------------------------------------------------------------------------- -@pytest.fixture(params=_PHYSICS_RENDERER_AOV_COMBINATIONS) -def dexsuite_kuka_allegro_lift_env(request): - """Build Dexsuite Kuka-Allegro Lift (single camera) for backend/renderer/data_type; reset, yield, close.""" +@pytest.mark.flaky(max_runs=3, min_passes=1) +@pytest.mark.parametrize("test_params", _PHYSICS_RENDERER_AOV_COMBINATIONS) +def test_dexsuite_kuka_allegro_lift(test_params): + """Camera output must contain at least one non-zero pixel (Dexsuite Kuka-Allegro Lift, single camera). + + The env setup is intentionally inlined (not delegated to a yield fixture) so that + ``@pytest.mark.flaky`` reruns the full env-creation + render + validation cycle on + each attempt. With a yield fixture the fixture body runs only once, meaning every + retry would see the same cached image — making the flaky mark ineffective. + """ from isaaclab.envs import ManagerBasedRLEnv from isaaclab_tasks.manager_based.manipulation.dexsuite.config.kuka_allegro.dexsuite_kuka_allegro_env_cfg import ( DexsuiteKukaAllegroLiftEnvCfg, ) - physics_backend, renderer, data_type = request.param + physics_backend, renderer, data_type = test_params # Dexsuite data type has explicit resolution suffix (64, 128, 256). We only test 64x64. override_args = [f"presets={physics_backend},{renderer},{data_type}64,single_camera,cube"] @@ -837,30 +844,23 @@ def dexsuite_kuka_allegro_lift_env(request): if point_cloud_term is not None: point_cloud_term.params["visualize"] = False + test_name = "dexsuite_kuka" env = None try: env = ManagerBasedRLEnv(env_cfg) - _maybe_save_stage("dexsuite_kuka", physics_backend, renderer, data_type) - yield physics_backend, renderer, data_type, env + _maybe_save_stage(test_name, physics_backend, renderer, data_type) + _validate_camera_outputs( + test_name, + physics_backend, + renderer, + env.scene.sensors["base_camera"].data.output, + max_different_pixels_percentage=_MAX_DIFFERENT_PIXELS_PERCENTAGE_BY_ENV_NAME[test_name], + ) finally: if env is not None: env.close() -@pytest.mark.flaky(max_runs=3, min_passes=1) -def test_dexsuite_kuka_allegro_lift(dexsuite_kuka_allegro_lift_env): - """Camera output must contain at least one non-zero pixel (Dexsuite Kuka-Allegro Lift, single camera).""" - physics_backend, renderer, _, env = dexsuite_kuka_allegro_lift_env - test_name = "dexsuite_kuka" - _validate_camera_outputs( - test_name, - physics_backend, - renderer, - env.scene.sensors["base_camera"].data.output, - max_different_pixels_percentage=_MAX_DIFFERENT_PIXELS_PERCENTAGE_BY_ENV_NAME[test_name], - ) - - # --------------------------------------------------------------------------- # Registered tasks (camera-based observations) # --------------------------------------------------------------------------- diff --git a/source/isaaclab_teleop/config/extension.toml b/source/isaaclab_teleop/config/extension.toml index 13c63e04ab99..61273888c608 100644 --- a/source/isaaclab_teleop/config/extension.toml +++ b/source/isaaclab_teleop/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.3.6" +version = "0.3.8" # Description title = "Isaac Lab Teleop" diff --git a/source/isaaclab_teleop/docs/CHANGELOG.rst b/source/isaaclab_teleop/docs/CHANGELOG.rst index 9ad0bf77ecd2..8a12edb8aef1 100644 --- a/source/isaaclab_teleop/docs/CHANGELOG.rst +++ b/source/isaaclab_teleop/docs/CHANGELOG.rst @@ -1,6 +1,27 @@ Changelog --------- +0.3.8 (2026-04-24) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Switched :class:`~isaaclab_teleop.xr_anchor_utils.XrAnchorSynchronizer` to import + ``get_current_stage`` from :mod:`isaaclab.sim.utils.stage` instead of + ``isaacsim.core.experimental.utils.stage``, aligning with the Isaac Lab API. + + +0.3.7 (2026-04-22) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Updated XR anchor prim creation to use :func:`isaaclab.sim.utils.prims.create_prim` + instead of ``isaacsim.core.experimental.prims.XformPrim``. + + 0.3.6 (2026-04-21) ~~~~~~~~~~~~~~~~~~~ @@ -45,7 +66,6 @@ Fixed ``stop()`` while the simulation loop was still running. The callback now uses the same graceful teardown path as the XR-disabled handler. - 0.3.5 (2026-04-06) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_teleop/isaaclab_teleop/deprecated/openxr/manus_vive_utils.py b/source/isaaclab_teleop/isaaclab_teleop/deprecated/openxr/manus_vive_utils.py index 97056b21ac69..a67a738c0c83 100644 --- a/source/isaaclab_teleop/isaaclab_teleop/deprecated/openxr/manus_vive_utils.py +++ b/source/isaaclab_teleop/isaaclab_teleop/deprecated/openxr/manus_vive_utils.py @@ -9,7 +9,7 @@ import numpy as np -from isaacsim.core.utils.extensions import enable_extension +from isaacsim.core.experimental.utils.app import enable_extension # For testing purposes, we need to mock the XRCore XRCore, XRPoseValidityFlags = None, None diff --git a/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_manager.py b/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_manager.py index a225b7f6297f..d39cdcbe84ad 100644 --- a/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_manager.py +++ b/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_manager.py @@ -24,8 +24,7 @@ with contextlib.suppress(ModuleNotFoundError): from omni.kit.xr.core import XRCore, XRCoreEventType -with contextlib.suppress(ModuleNotFoundError): - from isaacsim.core.prims import SingleXFormPrim +from isaaclab.sim.utils.prims import create_prim as _create_prim logger = logging.getLogger(__name__) @@ -77,14 +76,12 @@ def __init__(self, xr_cfg: XrCfg): self._xr_anchor_headset_path = "/World/XRAnchor" # Create the XR anchor prim in USD. - # XrCfg.anchor_rot is xyzw; SingleXFormPrim expects wxyz. + # XrCfg.anchor_rot is xyzw; create_prim orientation expects xyzw. x, y, z, w = self._xr_cfg.anchor_rot try: - _ = SingleXFormPrim( - self._xr_anchor_headset_path, - position=self._xr_cfg.anchor_pos, - orientation=np.array([w, x, y, z], dtype=np.float64), - ) + pos = np.asarray(self._xr_cfg.anchor_pos, dtype=np.float64) + quat_xyzw = np.asarray([x, y, z, w], dtype=np.float64) + _create_prim(self._xr_anchor_headset_path, prim_type="Xform", position=pos, orientation=quat_xyzw) except Exception as e: logger.warning(f"Failed to create XR anchor prim: {e}") diff --git a/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_utils.py b/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_utils.py index 035630959fb8..196de3ce56b9 100644 --- a/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_utils.py +++ b/source/isaaclab_teleop/isaaclab_teleop/xr_anchor_utils.py @@ -17,7 +17,7 @@ logger = logging.getLogger(__name__) from isaaclab.sim import SimulationContext -from isaaclab.sim.utils.stage import get_current_stage_id +from isaaclab.sim.utils.stage import get_current_stage, get_current_stage_id from .xr_cfg import XrAnchorRotationMode @@ -51,8 +51,6 @@ def __init__(self, xr_core: Any, xr_cfg: Any, xr_anchor_headset_path: str): # Resolve USD layer identifier of the anchor for updates try: - from isaacsim.core.utils.stage import get_current_stage - stage = get_current_stage() xr_anchor_headset_prim = stage.GetPrimAtPath(self._xr_anchor_headset_path) prim_stack = xr_anchor_headset_prim.GetPrimStack() if xr_anchor_headset_prim is not None else None diff --git a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py index ca5117f62d09..ced2935897ae 100644 --- a/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py +++ b/source/isaaclab_visualizers/isaaclab_visualizers/kit/kit_visualizer.py @@ -11,7 +11,7 @@ import logging from typing import TYPE_CHECKING -from pxr import Usd, UsdGeom, Vt +from pxr import Gf, Usd, UsdGeom, Vt from isaaclab.app.settings_manager import get_settings_manager from isaaclab.visualizers.base_visualizer import BaseVisualizer @@ -340,17 +340,22 @@ async def _dock_viewport_async(self, viewport_name: str, dock_position) -> None: def _set_viewport_camera(self, position: tuple[float, float, float], target: tuple[float, float, float]) -> None: """Apply eye/target camera view to the active viewport.""" - import isaacsim.core.utils.viewports as isaacsim_viewports + if self._viewport_api is None: + return - camera_path = None - if self._viewport_api is not None: - camera_path = self._viewport_api.get_active_camera() + try: + from omni.kit.viewport.utility.camera_state import ViewportCameraState + except ImportError as exc: + logger.warning("[KitVisualizer] Viewport camera update skipped: %s", exc) + return + + camera_path = self._viewport_api.get_active_camera() if not camera_path: camera_path = "/OmniverseKit_Persp" - kwargs = {"eye": list(position), "target": list(target), "camera_prim_path": camera_path} - if self._viewport_api is not None: - kwargs["viewport_api"] = self._viewport_api - isaacsim_viewports.set_camera_view(**kwargs) + + camera_state = ViewportCameraState(camera_path, self._viewport_api) + camera_state.set_position_world(Gf.Vec3d(float(position[0]), float(position[1]), float(position[2])), True) + camera_state.set_target_world(Gf.Vec3d(float(target[0]), float(target[1]), float(target[2])), True) def _apply_cfg_camera_pose_if_configured(self) -> None: """Apply configured camera pose from eye/lookat."""