diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index a618ddc0e13..c2fb652e842 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -18,9 +18,9 @@ import omni.kit.app import omni.timeline from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager -from isaacsim.core.utils.stage import get_current_stage import isaaclab.sim as sim_utils +from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: from .asset_base_cfg import AssetBaseCfg diff --git a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_data.py b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_data.py index ee83900376f..b809fd89f35 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_data.py +++ b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_data.py @@ -9,7 +9,7 @@ import omni.physics.tensors.impl.api as physx import isaaclab.utils.math as math_utils -from isaaclab.sim.utils import get_current_stage_id +from isaaclab.sim.utils.stage import get_current_stage_id from isaaclab.utils.buffers import TimestampedBuffer diff --git a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_data.py b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_data.py index 328010bb14f..415d1617285 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_data.py +++ b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_data.py @@ -9,7 +9,7 @@ import omni.physics.tensors.impl.api as physx import isaaclab.utils.math as math_utils -from isaaclab.sim.utils import get_current_stage_id +from isaaclab.sim.utils.stage import get_current_stage_id from isaaclab.utils.buffers import TimestampedBuffer diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index 0e7429117fc..fc565a67ec1 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -26,7 +26,7 @@ from isaaclab.managers import EventManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext -from isaaclab.sim.utils import attach_stage_to_usd_context, use_stage +from isaaclab.sim.utils.stage import attach_stage_to_usd_context, use_stage from isaaclab.utils.noise import NoiseModel from isaaclab.utils.timer import Timer diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index e43c4db7a28..9a8d265a8f5 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -27,7 +27,7 @@ from isaaclab.managers import EventManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext -from isaaclab.sim.utils import attach_stage_to_usd_context, use_stage +from isaaclab.sim.utils.stage import attach_stage_to_usd_context, use_stage from isaaclab.utils.noise import NoiseModel from isaaclab.utils.timer import Timer diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 9ddc538aa41..b5e9b79905c 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -17,7 +17,7 @@ from isaaclab.managers import ActionManager, EventManager, ObservationManager, RecorderManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext -from isaaclab.sim.utils import attach_stage_to_usd_context, use_stage +from isaaclab.sim.utils.stage import attach_stage_to_usd_context, use_stage from isaaclab.ui.widgets import ManagerLiveVisualizer from isaaclab.utils.timer import Timer diff --git a/source/isaaclab/isaaclab/envs/mdp/events.py b/source/isaaclab/isaaclab/envs/mdp/events.py index 923fd1597ab..7ea6d7b2e0a 100644 --- a/source/isaaclab/isaaclab/envs/mdp/events.py +++ b/source/isaaclab/isaaclab/envs/mdp/events.py @@ -22,7 +22,6 @@ import carb import omni.physics.tensors.impl.api as physx from isaacsim.core.utils.extensions import enable_extension -from isaacsim.core.utils.stage import get_current_stage from pxr import Gf, Sdf, UsdGeom, Vt import isaaclab.sim as sim_utils @@ -30,6 +29,7 @@ from isaaclab.actuators import ImplicitActuator from isaaclab.assets import Articulation, DeformableObject, RigidObject from isaaclab.managers import EventTermCfg, ManagerTermBase, SceneEntityCfg +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.terrains import TerrainImporter from isaaclab.utils.version import compare_versions diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 6744238b5a9..5df0ce00705 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -15,9 +15,9 @@ import omni.kit.app import omni.kit.commands import omni.usd -from isaacsim.core.utils.stage import get_current_stage from pxr import PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.ui.widgets import ManagerLiveVisualizer if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/markers/visualization_markers.py b/source/isaaclab/isaaclab/markers/visualization_markers.py index ce4611289bc..e37200b920d 100644 --- a/source/isaaclab/isaaclab/markers/visualization_markers.py +++ b/source/isaaclab/isaaclab/markers/visualization_markers.py @@ -23,16 +23,14 @@ import torch from dataclasses import MISSING -import isaacsim.core.utils.stage as stage_utils import omni.kit.commands import omni.log import omni.physx.scripts.utils as physx_utils -from isaacsim.core.utils.stage import get_current_stage from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics, Vt import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.spawners import SpawnerCfg -from isaaclab.sim.utils import attach_stage_to_usd_context from isaaclab.utils.configclass import configclass from isaaclab.utils.math import convert_quat @@ -148,7 +146,7 @@ def __init__(self, cfg: VisualizationMarkersCfg): # get next free path for the prim prim_path = stage_utils.get_next_free_path(cfg.prim_path) # create a new prim - self.stage = get_current_stage() + self.stage = stage_utils.get_current_stage() self._instancer_manager = UsdGeom.PointInstancer.Define(self.stage, prim_path) # store inputs self.prim_path = prim_path @@ -398,7 +396,7 @@ def _process_prototype_prim(self, prim: Usd.Prim): if child_prim.IsA(UsdGeom.Gprim): # early attach stage to usd context if stage is in memory # since stage in memory is not supported by the "ChangePropertyCommand" kit command - attach_stage_to_usd_context(attaching_early=True) + stage_utils.attach_stage_to_usd_context(attaching_early=True) # invisible to secondary rays such as depth images omni.kit.commands.execute( diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 15739c33ad7..2e7b2327301 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -12,7 +12,6 @@ import omni.usd from isaacsim.core.cloner import GridCloner from isaacsim.core.prims import XFormPrim -from isaacsim.core.utils.stage import get_current_stage from isaacsim.core.version import get_version from pxr import PhysxSchema @@ -32,7 +31,7 @@ ) from isaaclab.sensors import ContactSensorCfg, FrameTransformerCfg, SensorBase, SensorBaseCfg from isaaclab.sim import SimulationContext -from isaaclab.sim.utils import get_current_stage_id +from isaaclab.sim.utils.stage import get_current_stage, get_current_stage_id from isaaclab.terrains import TerrainImporter, TerrainImporterCfg from .interactive_scene_cfg import InteractiveSceneCfg diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index 8d3fe257df6..5f2090eb016 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -13,7 +13,6 @@ from typing import TYPE_CHECKING, Any, Literal import carb -import isaacsim.core.utils.stage as stage_utils import omni.kit.commands import omni.usd from isaacsim.core.prims import XFormPrim @@ -21,6 +20,7 @@ from pxr import Sdf, UsdGeom import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.sensors as sensor_utils from isaaclab.utils import to_camel_case from isaaclab.utils.array import convert_to_torch diff --git a/source/isaaclab/isaaclab/sensors/imu/imu.py b/source/isaaclab/isaaclab/sensors/imu/imu.py index 1c700eeedb2..5930c61614f 100644 --- a/source/isaaclab/isaaclab/sensors/imu/imu.py +++ b/source/isaaclab/isaaclab/sensors/imu/imu.py @@ -9,11 +9,11 @@ from collections.abc import Sequence from typing import TYPE_CHECKING -import isaacsim.core.utils.stage as stage_utils from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.markers import VisualizationMarkers diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py index 3bf8729b78b..c26a6c650cd 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py @@ -9,10 +9,10 @@ from collections.abc import Sequence from typing import TYPE_CHECKING, ClassVar, Literal -import isaacsim.core.utils.stage as stage_utils import omni.physics.tensors.impl.api as physx from isaacsim.core.prims import XFormPrim +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.sensors.camera import CameraData from isaaclab.utils.warp import raycast_mesh diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index aab993cc526..eb1f6ffb8d4 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -23,9 +23,9 @@ import omni.kit.app import omni.timeline from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager -from isaacsim.core.utils.stage import get_current_stage import isaaclab.sim as sim_utils +from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: from .sensor_base_cfg import SensorBaseCfg diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py index 482b6745842..b260d18c77f 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py @@ -10,10 +10,11 @@ import omni.log import omni.physx.scripts.utils as physx_utils -from isaacsim.core.utils.stage import get_current_stage from omni.physx.scripts import deformableUtils as deformable_utils from pxr import PhysxSchema, Usd, UsdPhysics +from isaaclab.sim.utils.stage import get_current_stage + from ..utils import ( apply_nested, find_global_fixed_joint_prim, diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 83277635acf..1618d6da821 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -21,7 +21,6 @@ import carb import flatdict -import isaacsim.core.utils.stage as stage_utils import omni.log import omni.physx import omni.usd @@ -32,7 +31,7 @@ from isaacsim.core.version import get_version from pxr import Gf, PhysxSchema, Sdf, Usd, UsdPhysics -from isaaclab.sim.utils import create_new_stage_in_memory, use_stage +import isaaclab.sim.utils.stage as stage_utils from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg @@ -134,7 +133,7 @@ def __init__(self, cfg: SimulationCfg | None = None): # create stage in memory if requested if self.cfg.create_stage_in_memory: - self._initial_stage = create_new_stage_in_memory() + self._initial_stage = stage_utils.create_new_stage_in_memory() else: self._initial_stage = omni.usd.get_context().get_stage() @@ -613,7 +612,7 @@ async def reset_async(self, soft: bool = False): def _init_stage(self, *args, **kwargs) -> Usd.Stage: _ = super()._init_stage(*args, **kwargs) - with use_stage(self.get_initial_stage()): + with stage_utils.use_stage(self.get_initial_stage()): # a stage update here is needed for the case when physics_dt != rendering_dt, otherwise the app crashes # when in headless mode self.set_setting("/app/player/playSimulations", False) diff --git a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py index a3c8a44015a..15d4cc2d106 100644 --- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py +++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py @@ -18,16 +18,9 @@ except ModuleNotFoundError: from pxr import Semantics -from isaacsim.core.utils.stage import get_current_stage - from isaaclab.sim import converters, schemas -from isaaclab.sim.utils import ( - bind_physics_material, - bind_visual_material, - clone, - is_current_stage_in_memory, - select_usd_variants, -) +from isaaclab.sim.utils import bind_physics_material, bind_visual_material, clone, select_usd_variants +from isaaclab.sim.utils.stage import get_current_stage, is_current_stage_in_memory from isaaclab.utils.assets import check_usd_path_with_timeout if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py index e8977a14fd2..293c81f0000 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py @@ -8,10 +8,10 @@ from typing import TYPE_CHECKING import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.utils.stage import get_current_stage from pxr import PhysxSchema, Usd, UsdPhysics, UsdShade from isaaclab.sim.utils import clone, safe_set_attribute_on_usd_schema +from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: from . import physics_materials_cfg diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index 3c79f6f679e..fc4c5031913 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -12,7 +12,7 @@ import omni.log from pxr import Usd -from isaaclab.sim.utils import attach_stage_to_usd_context, clone, safe_set_attribute_on_usd_prim +from isaaclab.sim.utils.stage import attach_stage_to_usd_context, clone, safe_set_attribute_on_usd_prim from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py index 0a385902a55..a84d43d38ae 100644 --- a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py +++ b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py @@ -12,7 +12,8 @@ import omni.log from pxr import Sdf, Usd -from isaaclab.sim.utils import attach_stage_to_usd_context, clone +from isaaclab.sim.utils import clone +from isaaclab.sim.utils.stage import attach_stage_to_usd_context from isaaclab.utils import to_camel_case if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py index 9f339aa70c7..a0a7ca86042 100644 --- a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py +++ b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py @@ -11,11 +11,10 @@ import carb import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils -from isaacsim.core.utils.stage import get_current_stage from pxr import Sdf, Usd import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.spawners.from_files import UsdFileCfg if TYPE_CHECKING: @@ -48,7 +47,7 @@ def spawn_multi_asset( The created prim at the first prim path. """ # get stage handle - stage = get_current_stage() + stage = stage_utils.get_current_stage() # resolve: {SPAWN_NS}/AssetName # note: this assumes that the spawn namespace already exists in the stage diff --git a/source/isaaclab/isaaclab/sim/utils/__init__.py b/source/isaaclab/isaaclab/sim/utils/__init__.py new file mode 100644 index 00000000000..9d1dcbd0e33 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/utils/__init__.py @@ -0,0 +1,6 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from .utils import * # noqa: F401, F403 diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py new file mode 100644 index 00000000000..f3fe2d93b77 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -0,0 +1,795 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import builtins +import contextlib +import threading +import typing +from collections.abc import Generator + +import carb +import omni +import omni.kit.app +import usdrt +from isaacsim.core.utils.carb import get_carb_setting +from isaacsim.core.version import get_version +from omni.metrics.assembler.core import get_metrics_assembler_interface +from omni.usd.commands import DeletePrimsCommand +from pxr import Sdf, Usd, UsdGeom, UsdUtils + +_context = threading.local() # thread-local storage to handle nested contexts and concurrent access + + +AXES_TOKEN = { + "X": UsdGeom.Tokens.x, + "x": UsdGeom.Tokens.x, + "Y": UsdGeom.Tokens.y, + "y": UsdGeom.Tokens.y, + "Z": UsdGeom.Tokens.z, + "z": UsdGeom.Tokens.z, +} +"""Mapping from axis name to axis USD token + + >>> import isaacsim.core.utils.constants as constants_utils + >>> + >>> # get the x-axis USD token + >>> constants_utils.AXES_TOKEN['x'] + X + >>> constants_utils.AXES_TOKEN['X'] + X +""" + + +def attach_stage_to_usd_context(attaching_early: bool = False): + """Attaches the current USD stage in memory to the USD context. + + This function should be called during or after scene is created and before stage is simulated or rendered. + + Note: + If the stage is not in memory or rendering is not enabled, this function will return without attaching. + + Args: + attaching_early: Whether to attach the stage to the usd context before stage is created. Defaults to False. + """ + + from isaacsim.core.simulation_manager import SimulationManager + + from isaaclab.sim.simulation_context import SimulationContext + + # if Isaac Sim version is less than 5.0, stage in memory is not supported + isaac_sim_version = float(".".join(get_version()[2])) + if isaac_sim_version < 5: + return + + # if stage is not in memory, we can return early + if not is_current_stage_in_memory(): + return + + # attach stage to physx + stage_id = get_current_stage_id() + physx_sim_interface = omni.physx.get_physx_simulation_interface() + physx_sim_interface.attach_stage(stage_id) + + # this carb flag is equivalent to if rendering is enabled + carb_setting = carb.settings.get_settings() + is_rendering_enabled = get_carb_setting(carb_setting, "/physics/fabricUpdateTransformations") + + # if rendering is not enabled, we don't need to attach it + if not is_rendering_enabled: + return + + # early attach warning msg + if attaching_early: + omni.log.warn( + "Attaching stage in memory to USD context early to support an operation which doesn't support stage in" + " memory." + ) + + # skip this callback to avoid wiping the stage after attachment + SimulationContext.instance().skip_next_stage_open_callback() + + # disable stage open callback to avoid clearing callbacks + SimulationManager.enable_stage_open_callback(False) + + # enable physics fabric + SimulationContext.instance()._physics_context.enable_fabric(True) + + # attach stage to usd context + omni.usd.get_context().attach_stage_with_callback(stage_id) + + # attach stage to physx + physx_sim_interface = omni.physx.get_physx_simulation_interface() + physx_sim_interface.attach_stage(stage_id) + + # re-enable stage open callback + SimulationManager.enable_stage_open_callback(True) + + +def is_current_stage_in_memory() -> bool: + """Checks if the current stage is in memory. + + This function compares the stage id of the current USD stage with the stage id of the USD context stage. + + Returns: + Whether the current stage is in memory. + """ + + # grab current stage id + stage_id = get_current_stage_id() + + # grab context stage id + context_stage = omni.usd.get_context().get_stage() + with use_stage(context_stage): + context_stage_id = get_current_stage_id() + + # check if stage ids are the same + return stage_id != context_stage_id + + +@contextlib.contextmanager +def use_stage(stage: Usd.Stage) -> Generator[None, None, None]: + """Context manager that sets a thread-local stage, if supported. + + In Isaac Sim < 5.0, this is a no-op to maintain compatibility. + + Args: + stage: The stage to set temporarily. + + Raises: + AssertionError: If the stage is not a USD stage instance. + + Example: + + .. code-block:: python + + >>> from pxr import Usd + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_in_memory = Usd.Stage.CreateInMemory() + >>> with stage_utils.use_stage(stage_in_memory): + ... # operate on the specified stage + ... pass + >>> # operate on the default stage attached to the USD context + """ + isaac_sim_version = float(".".join(get_version()[2])) + if isaac_sim_version < 5: + omni.log.warn("[Compat] Isaac Sim < 5.0 does not support thread-local stage contexts. Skipping use_stage().") + yield # no-op + else: + # check stage + assert isinstance(stage, Usd.Stage), f"Expected a USD stage instance, got: {type(stage)}" + # store previous context value if it exists + previous_stage = getattr(_context, "stage", None) + # set new context value + try: + _context.stage = stage + yield + # remove context value or restore previous one if it exists + finally: + if previous_stage is None: + delattr(_context, "stage") + else: + _context.stage = previous_stage + + +def get_current_stage(fabric: bool = False) -> Usd.Stage | usdrt.Usd._Usd.Stage: + """Get the current open USD or Fabric stage + + Args: + fabric: True to get the fabric stage. False to get the USD stage. Defaults to False. + + Returns: + The USD or Fabric stage as specified by the input arg fabric. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.get_current_stage() + Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x7fba6c04f840:World7.usd'), + sessionLayer=Sdf.Find('anon:0x7fba6c01c5c0:World7-session.usda'), + pathResolverContext=) + """ + stage = getattr(_context, "stage", omni.usd.get_context().get_stage()) + if fabric: + stage_cache = UsdUtils.StageCache.Get() + stage_id = stage_cache.GetId(stage).ToLongInt() + if stage_id < 0: + stage_id = stage_cache.Insert(stage).ToLongInt() + return usdrt.Usd.Stage.Attach(stage_id) + return stage + + +def get_current_stage_id() -> int: + """Get the current open stage id + + Returns: + The current open stage id. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.get_current_stage_id() + 1234567890 + """ + stage = get_current_stage() + stage_cache = UsdUtils.StageCache.Get() + stage_id = stage_cache.GetId(stage).ToLongInt() + if stage_id < 0: + stage_id = stage_cache.Insert(stage).ToLongInt() + return stage_id + + +def update_stage() -> None: + """Update the current USD stage. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.update_stage() + """ + omni.kit.app.get_app_interface().update() + + +# TODO: make a generic util for setting all layer properties +def set_stage_up_axis(axis: str = "z") -> None: + """Change the up axis of the current stage + + Args: + axis (UsdGeom.Tokens, optional): valid values are ``"x"``, ``"y"`` and ``"z"`` + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> # set stage up axis to Y-up + >>> stage_utils.set_stage_up_axis("y") + """ + stage = get_current_stage() + if stage is None: + raise Exception("There is no stage currently opened") + rootLayer = stage.GetRootLayer() + rootLayer.SetPermissionToEdit(True) + with Usd.EditContext(stage, rootLayer): + UsdGeom.SetStageUpAxis(stage, AXES_TOKEN[axis]) + + +def get_stage_up_axis() -> str: + """Get the current up-axis of USD stage. + + Returns: + str: The up-axis of the stage. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.get_stage_up_axis() + Z + """ + stage = get_current_stage() + return UsdGeom.GetStageUpAxis(stage) + + +def clear_stage(predicate: typing.Callable[[str], bool] | None = None) -> None: + """Deletes all prims in the stage without populating the undo command buffer + + Args: + predicate: user defined function that takes a prim_path (str) as input and returns True/False if the prim + should/shouldn't be deleted. If predicate is None, a default is used that deletes all prims + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> # clear the whole stage + >>> stage_utils.clear_stage() + >>> + >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. + >>> # Delete only the prims of type Cube + >>> predicate = lambda path: prims_utils.get_prim_type_name(path) == "Cube" + >>> stage_utils.clear_stage(predicate) # after the execution the stage will be /World + """ + # Note: Need to import this here to prevent circular dependencies. + from isaaclab.utils.prims import ( + get_all_matching_child_prims, + get_prim_path, + is_prim_ancestral, + is_prim_hidden_in_stage, + is_prim_no_delete, + ) + + def default_predicate(prim_path: str): + # prim = get_prim_at_path(prim_path) + # skip prims that we cannot delete + if is_prim_no_delete(prim_path): + return False + if is_prim_hidden_in_stage(prim_path): + return False + if is_prim_ancestral(prim_path): + return False + if prim_path == "/": + return False + if prim_path.startswith("/Render"): + return False + return True + + if predicate is None: + prims = get_all_matching_child_prims("/", default_predicate) + prim_paths_to_delete = [get_prim_path(prim) for prim in prims] + DeletePrimsCommand(prim_paths_to_delete).do() + else: + prims = get_all_matching_child_prims("/", predicate) + prim_paths_to_delete = [get_prim_path(prim) for prim in prims] + DeletePrimsCommand(prim_paths_to_delete).do() + + if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False: + omni.kit.app.get_app_interface().update() + + +def print_stage_prim_paths(fabric: bool = False) -> None: + """Traverses the stage and prints all prim (hidden or not) paths. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. + >>> stage_utils.print_stage_prim_paths() + /Render + /World + /World/Cube + /World/Cube_01 + /World/Cube_02 + /OmniverseKit_Persp + /OmniverseKit_Front + /OmniverseKit_Top + /OmniverseKit_Right + """ + # Note: Need to import this here to prevent circular dependencies. + from isaaclab.utils.prims import get_prim_path + + for prim in traverse_stage(fabric=fabric): + prim_path = get_prim_path(prim) + print(prim_path) + + +def add_reference_to_stage(usd_path: str, prim_path: str, prim_type: str = "Xform") -> Usd.Prim: + """Add USD reference to the opened stage at specified prim path. + + Adds a reference to an external USD file at the specified prim path on the current stage. + If the prim does not exist, it will be created with the specified type. + This function also handles stage units verification to ensure compatibility. + + Args: + usd_path: The path to USD file to reference. + prim_path: The prim path where the reference will be attached. + prim_type: The type of prim to create if it doesn't exist. Defaults to "Xform". + + Returns: + The USD prim at the specified prim path. + + Raises: + FileNotFoundError: When the input USD file is not found at the specified path. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> # load an USD file (franka.usd) to the stage under the path /World/panda + >>> prim = stage_utils.add_reference_to_stage( + ... usd_path="/home//Documents/Assets/Robots/FrankaRobotics/FrankaPanda/franka.usd", + ... prim_path="/World/panda" + ... ) + >>> prim + Usd.Prim() + """ + stage = get_current_stage() + prim = stage.GetPrimAtPath(prim_path) + if not prim.IsValid(): + prim = stage.DefinePrim(prim_path, prim_type) + # omni.log.info("Loading Asset from path {} ".format(usd_path)) + # Handle units + sdf_layer = Sdf.Layer.FindOrOpen(usd_path) + if not sdf_layer: + pass + # omni.log.info(f"Could not get Sdf layer for {usd_path}") + else: + stage_id = UsdUtils.StageCache.Get().GetId(stage).ToLongInt() + ret_val = get_metrics_assembler_interface().check_layers( + stage.GetRootLayer().identifier, sdf_layer.identifier, stage_id + ) + if ret_val["ret_val"]: + try: + import omni.metrics.assembler.ui + + payref = Sdf.Reference(usd_path) + omni.kit.commands.execute("AddReference", stage=stage, prim_path=prim.GetPath(), reference=payref) + except Exception as exc: + # omni.log.warn( + # f"The USD file {usd_path} used for a reference does have divergent units, please either enable omni.usd.metrics.assembler.ui or convert the file into right units." + # ) + success_bool = prim.GetReferences().AddReference(usd_path) + if not success_bool: + raise FileNotFoundError(f"The usd file at path {usd_path} provided wasn't found") + else: + success_bool = prim.GetReferences().AddReference(usd_path) + if not success_bool: + raise FileNotFoundError(f"The usd file at path {usd_path} provided wasn't found") + + return prim + + +def create_new_stage() -> Usd.Stage: + """Create a new stage attached to the USD context. + + Returns: + Usd.Stage: The created USD stage. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.create_new_stage() + Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x7fba6c04f840:World7.usd'), + sessionLayer=Sdf.Find('anon:0x7fba6c01c5c0:World7-session.usda'), + pathResolverContext=) + """ + return omni.usd.get_context().new_stage() + + +def create_new_stage_in_memory() -> Usd.Stage: + """Creates a new stage in memory, if supported. + + Returns: + The new stage in memory. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.create_new_stage_in_memory() + Usd.Stage.Open(rootLayer=Sdf.Find('anon:0xf7b00e0:tmp.usda'), + sessionLayer=Sdf.Find('anon:0xf7cd2e0:tmp-session.usda'), + pathResolverContext=) + """ + isaac_sim_version = float(".".join(get_version()[2])) + if isaac_sim_version < 5: + omni.log.warn( + "[Compat] Isaac Sim < 5.0 does not support creating a new stage in memory. Falling back to creating a new" + " stage attached to USD context." + ) + return create_new_stage() + else: + return Usd.Stage.CreateInMemory() + + +def open_stage(usd_path: str) -> bool: + """Open the given usd file and replace currently opened stage. + + Args: + usd_path (str): Path to the USD file to open. + + Raises: + ValueError: When input path is not a supported file type by USD. + + Returns: + bool: True if operation is successful, otherwise false. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.open_stage("/home//Documents/Assets/Robots/FrankaRobotics/FrankaPanda/franka.usd") + True + """ + if not Usd.Stage.IsSupportedFile(usd_path): + raise ValueError("Only USD files can be loaded with this method") + usd_context = omni.usd.get_context() + usd_context.disable_save_to_recent_files() + result = omni.usd.get_context().open_stage(usd_path) + usd_context.enable_save_to_recent_files() + return result + + +def save_stage(usd_path: str, save_and_reload_in_place=True) -> bool: + """Save usd file to path, it will be overwritten with the current stage + + Args: + usd_path (str): File path to save the current stage to + save_and_reload_in_place (bool, optional): use ``save_as_stage`` to save and reload the root layer in place. Defaults to True. + + Raises: + ValueError: When input path is not a supported file type by USD. + + Returns: + bool: True if operation is successful, otherwise false. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.save_stage("/home//Documents/Save/stage.usd") + True + """ + if not Usd.Stage.IsSupportedFile(usd_path): + raise ValueError("Only USD files can be saved with this method") + + layer = Sdf.Layer.CreateNew(usd_path) + root_layer = get_current_stage().GetRootLayer() + layer.TransferContent(root_layer) + omni.usd.resolve_paths(root_layer.identifier, layer.identifier) + result = layer.Save() + if save_and_reload_in_place: + open_stage(usd_path) + + return result + + +def close_stage(callback_fn: typing.Callable | None = None) -> bool: + """Closes the current opened USD stage. + + .. note:: + + Once the stage is closed, it is necessary to open a new stage or create a new one in order to work on it. + + Args: + callback_fn: Callback function to call while closing. Defaults to None. + + Returns: + bool: True if operation is successful, otherwise false. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.close_stage() + True + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> def callback(*args, **kwargs): + ... print("callback:", args, kwargs) + ... + >>> stage_utils.close_stage(callback) + True + >>> stage_utils.close_stage(callback) + callback: (False, 'Stage opening or closing already in progress!!') {} + False + """ + if callback_fn is None: + result = omni.usd.get_context().close_stage() + else: + result = omni.usd.get_context().close_stage_with_callback(callback_fn) + return result + + +def traverse_stage(fabric=False) -> typing.Iterable: + """Traverse through prims (hidden or not) in the opened Usd stage. + + Returns: + Generator which yields prims from the stage in depth-first-traversal order. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. + >>> # Traverse through prims in the stage + >>> for prim in stage_utils.traverse_stage(): + >>> print(prim) + Usd.Prim() + Usd.Prim() + Usd.Prim() + Usd.Prim() + Usd.Prim() + Usd.Prim() + Usd.Prim() + Usd.Prim() + Usd.Prim() + """ + return get_current_stage(fabric=fabric).Traverse() + + +def is_stage_loading() -> bool: + """Convenience function to see if any files are being loaded. + + Returns: + bool: True if loading, False otherwise + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.is_stage_loading() + False + """ + context = omni.usd.get_context() + if context is None: + return False + else: + _, _, loading = context.get_stage_loading_status() + return loading > 0 + + +def set_stage_units(stage_units_in_meters: float) -> None: + """Set the stage meters per unit + + The most common units and their values are listed in the following table: + + +------------------+--------+ + | Unit | Value | + +==================+========+ + | kilometer (km) | 1000.0 | + +------------------+--------+ + | meters (m) | 1.0 | + +------------------+--------+ + | inch (in) | 0.0254 | + +------------------+--------+ + | centimeters (cm) | 0.01 | + +------------------+--------+ + | millimeter (mm) | 0.001 | + +------------------+--------+ + + Args: + stage_units_in_meters (float): units for stage + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.set_stage_units(1.0) + """ + if get_current_stage() is None: + raise Exception("There is no stage currently opened, init_stage needed before calling this func") + with Usd.EditContext(get_current_stage(), get_current_stage().GetRootLayer()): + UsdGeom.SetStageMetersPerUnit(get_current_stage(), stage_units_in_meters) + + +def get_stage_units() -> float: + """Get the stage meters per unit currently set + + The most common units and their values are listed in the following table: + + +------------------+--------+ + | Unit | Value | + +==================+========+ + | kilometer (km) | 1000.0 | + +------------------+--------+ + | meters (m) | 1.0 | + +------------------+--------+ + | inch (in) | 0.0254 | + +------------------+--------+ + | centimeters (cm) | 0.01 | + +------------------+--------+ + | millimeter (mm) | 0.001 | + +------------------+--------+ + + Returns: + float: current stage meters per unit + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> stage_utils.get_stage_units() + 1.0 + """ + return UsdGeom.GetStageMetersPerUnit(get_current_stage()) + + +def get_next_free_path(path: str, parent: str = None) -> str: + """Returns the next free usd path for the current stage + + Args: + path (str): path we want to check + parent (str, optional): Parent prim for the given path. Defaults to None. + + Returns: + str: a new path that is guaranteed to not exist on the current stage + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> + >>> # given the stage: /World/Cube, /World/Cube_01. + >>> # Get the next available path for /World/Cube + >>> stage_utils.get_next_free_path("/World/Cube") + /World/Cube_02 + """ + if parent is not None: + # remove trailing slash from parent and leading slash from path + path = omni.usd.get_stage_next_free_path( + get_current_stage(), parent.rstrip("/") + "/" + path.lstrip("/"), False + ) + else: + path = omni.usd.get_stage_next_free_path(get_current_stage(), path, True) + return path + + +def remove_deleted_references(): + """Clean up deleted references in the current USD stage. + + Removes any deleted items from both payload and references lists + for all prims in the stage's root layer. Prints information about + any deleted items that were cleaned up. + + Example: + + .. code-block:: python + + >>> import isaaclab.sim.utils.stage as stage_utils + >>> stage_utils.remove_deleted_references() + Removed 2 deleted payload items from + Removed 1 deleted reference items from + """ + stage = get_current_stage() + deleted_count = 0 + + for prim in stage.Traverse(): + prim_spec = stage.GetRootLayer().GetPrimAtPath(prim.GetPath()) + if not prim_spec: + continue + + # Clean payload references + payload_list = prim_spec.GetInfo("payload") + if payload_list.deletedItems: + deleted_payload_count = len(payload_list.deletedItems) + print(f"Removed {deleted_payload_count} deleted payload items from {prim.GetPath()}") + payload_list.deletedItems = [] + prim_spec.SetInfo("payload", payload_list) + deleted_count += deleted_payload_count + + # Clean prim references + references_list = prim_spec.GetInfo("references") + if references_list.deletedItems: + deleted_ref_count = len(references_list.deletedItems) + print(f"Removed {deleted_ref_count} deleted reference items from {prim.GetPath()}") + references_list.deletedItems = [] + prim_spec.SetInfo("references", references_list) + deleted_count += deleted_ref_count + + if deleted_count == 0: + print("No deleted references or payloads found in the stage.") diff --git a/source/isaaclab/isaaclab/sim/utils.py b/source/isaaclab/isaaclab/sim/utils/utils.py similarity index 89% rename from source/isaaclab/isaaclab/sim/utils.py rename to source/isaaclab/isaaclab/sim/utils/utils.py index 338ec5d843a..06ce77f977e 100644 --- a/source/isaaclab/isaaclab/sim/utils.py +++ b/source/isaaclab/isaaclab/sim/utils/utils.py @@ -7,23 +7,18 @@ from __future__ import annotations -import contextlib import functools import inspect import re -from collections.abc import Callable, Generator +from collections.abc import Callable from typing import TYPE_CHECKING, Any -import carb -import isaacsim.core.utils.stage as stage_utils import omni import omni.kit.commands import omni.log from isaacsim.core.cloner import Cloner -from isaacsim.core.utils.carb import get_carb_setting -from isaacsim.core.utils.stage import get_current_stage from isaacsim.core.version import get_version -from pxr import PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics, UsdShade, UsdUtils +from pxr import PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics, UsdShade # from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated try: @@ -31,12 +26,13 @@ except ModuleNotFoundError: from pxr import Semantics +from isaaclab.sim import schemas from isaaclab.utils.string import to_camel_case -from . import schemas +from .stage import attach_stage_to_usd_context, get_current_stage if TYPE_CHECKING: - from .spawners.spawner_cfg import SpawnerCfg + from ..spawners.spawner_cfg import SpawnerCfg """ Attribute - Setters. @@ -1033,149 +1029,3 @@ class TableVariants: f"Setting variant selection '{variant_selection}' for variant set '{variant_set_name}' on" f" prim '{prim_path}'." ) - - -""" -Stage management. -""" - - -def attach_stage_to_usd_context(attaching_early: bool = False): - """Attaches the current USD stage in memory to the USD context. - - This function should be called during or after scene is created and before stage is simulated or rendered. - - Note: - If the stage is not in memory or rendering is not enabled, this function will return without attaching. - - Args: - attaching_early: Whether to attach the stage to the usd context before stage is created. Defaults to False. - """ - - from isaacsim.core.simulation_manager import SimulationManager - - from isaaclab.sim.simulation_context import SimulationContext - - # if Isaac Sim version is less than 5.0, stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) - if isaac_sim_version < 5: - return - - # if stage is not in memory, we can return early - if not is_current_stage_in_memory(): - return - - # attach stage to physx - stage_id = get_current_stage_id() - physx_sim_interface = omni.physx.get_physx_simulation_interface() - physx_sim_interface.attach_stage(stage_id) - - # this carb flag is equivalent to if rendering is enabled - carb_setting = carb.settings.get_settings() - is_rendering_enabled = get_carb_setting(carb_setting, "/physics/fabricUpdateTransformations") - - # if rendering is not enabled, we don't need to attach it - if not is_rendering_enabled: - return - - # early attach warning msg - if attaching_early: - omni.log.warn( - "Attaching stage in memory to USD context early to support an operation which doesn't support stage in" - " memory." - ) - - # skip this callback to avoid wiping the stage after attachment - SimulationContext.instance().skip_next_stage_open_callback() - - # disable stage open callback to avoid clearing callbacks - SimulationManager.enable_stage_open_callback(False) - - # enable physics fabric - SimulationContext.instance()._physics_context.enable_fabric(True) - - # attach stage to usd context - omni.usd.get_context().attach_stage_with_callback(stage_id) - - # attach stage to physx - physx_sim_interface = omni.physx.get_physx_simulation_interface() - physx_sim_interface.attach_stage(stage_id) - - # re-enable stage open callback - SimulationManager.enable_stage_open_callback(True) - - -def is_current_stage_in_memory() -> bool: - """Checks if the current stage is in memory. - - This function compares the stage id of the current USD stage with the stage id of the USD context stage. - - Returns: - Whether the current stage is in memory. - """ - - # grab current stage id - stage_id = get_current_stage_id() - - # grab context stage id - context_stage = omni.usd.get_context().get_stage() - with use_stage(context_stage): - context_stage_id = get_current_stage_id() - - # check if stage ids are the same - return stage_id != context_stage_id - - -@contextlib.contextmanager -def use_stage(stage: Usd.Stage) -> Generator[None, None, None]: - """Context manager that sets a thread-local stage, if supported. - - In Isaac Sim < 5.0, this is a no-op to maintain compatibility. - - Args: - stage: The stage to set temporarily. - - Yields: - None - """ - isaac_sim_version = float(".".join(get_version()[2])) - if isaac_sim_version < 5: - omni.log.warn("[Compat] Isaac Sim < 5.0 does not support thread-local stage contexts. Skipping use_stage().") - yield # no-op - else: - with stage_utils.use_stage(stage): - yield - - -def create_new_stage_in_memory() -> Usd.Stage: - """Creates a new stage in memory, if supported. - - Returns: - The new stage in memory. - """ - isaac_sim_version = float(".".join(get_version()[2])) - if isaac_sim_version < 5: - omni.log.warn( - "[Compat] Isaac Sim < 5.0 does not support creating a new stage in memory. Falling back to creating a new" - " stage attached to USD context." - ) - return stage_utils.create_new_stage() - else: - return stage_utils.create_new_stage_in_memory() - - -def get_current_stage_id() -> int: - """Gets the current open stage id. - - This function is a reimplementation of :meth:`isaacsim.core.utils.stage.get_current_stage_id` for - backwards compatibility to Isaac Sim < 5.0. - - Returns: - The current open stage id. - """ - stage = get_current_stage() - stage_cache = UsdUtils.StageCache.Get() - stage_id = stage_cache.GetId(stage).ToLongInt() - if stage_id < 0: - stage_id = stage_cache.Insert(stage).ToLongInt() - return stage_id diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 0b84e09eff2..38b8f70784b 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -15,11 +15,11 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.assets import Articulation from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index b708b357218..9441a3b1596 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -15,11 +15,11 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.assets import Articulation from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg from isaaclab.markers import VisualizationMarkers 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 dbe12e8265f..420061175e5 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 @@ -34,7 +34,6 @@ import isaacsim.core.utils.nucleus as nucleus_utils import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni.kit.commands import omni.log import omni.physx @@ -44,6 +43,8 @@ from isaacsim.core.utils.viewports import set_camera_view from pxr import PhysxSchema, UsdPhysics +import isaaclab.sim.utils.stage as stage_utils + # check nucleus connection if nucleus_utils.get_assets_root_path() is None: msg = ( diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index 03955076b6e..34389cd0703 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -14,11 +14,11 @@ import torch -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.markers.config import FRAME_MARKER_CFG, POSITION_GOAL_MARKER_CFG from isaaclab.utils.math import random_orientation diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index e660274b862..67d7d379b31 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -23,13 +23,13 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni.replicator.core as rep import pytest from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, Usd, UsdGeom import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.utils import convert_dict_to_backend from isaaclab.utils.math import convert_quat diff --git a/source/isaaclab/test/sensors/test_frame_transformer.py b/source/isaaclab/test/sensors/test_frame_transformer.py index eda9f6019ab..5257e732420 100644 --- a/source/isaaclab/test/sensors/test_frame_transformer.py +++ b/source/isaaclab/test/sensors/test_frame_transformer.py @@ -16,10 +16,10 @@ import scipy.spatial.transform as tf import torch -import isaacsim.core.utils.stage as stage_utils import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.assets import RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg diff --git a/source/isaaclab/test/sensors/test_imu.py b/source/isaaclab/test/sensors/test_imu.py index 7f621a36574..d8074e36234 100644 --- a/source/isaaclab/test/sensors/test_imu.py +++ b/source/isaaclab/test/sensors/test_imu.py @@ -17,10 +17,10 @@ import pathlib import torch -import isaacsim.core.utils.stage as stage_utils import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg, RigidObjectCfg diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 7408ae06b75..c46170798cf 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -21,7 +21,6 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni.replicator.core as rep import pytest from flaky import flaky @@ -29,6 +28,7 @@ from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors.camera import TiledCamera, TiledCameraCfg diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index dd693bbc3f1..b3c43647b9c 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -21,12 +21,12 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni.replicator.core as rep import pytest from pxr import Gf import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.sensors.ray_caster import RayCasterCamera, RayCasterCameraCfg, patterns from isaaclab.sim import PinholeCameraCfg diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 9f82198214c..e10165347ca 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -19,10 +19,10 @@ from dataclasses import dataclass import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors import SensorBase, SensorBaseCfg from isaaclab.utils import configclass diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index fdef7a3ae5c..5bf0d4d75ad 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -21,12 +21,13 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni.replicator.core as rep import pytest from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom +import isaaclab.sim.utils.stage as stage_utils + # from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated try: import Semantics diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index 90bfc557c78..cc5b8e70dd2 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -18,12 +18,12 @@ import tempfile import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni import pytest from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdGeom, UsdPhysics +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import MeshConverter, MeshConverterCfg from isaaclab.sim.schemas import schemas_cfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR, retrieve_file_path diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 5921b12fc6c..0fe48362b22 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -15,11 +15,11 @@ import os import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import MjcfConverter, MjcfConverterCfg diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index 29b451f4214..d396ffbd798 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -15,12 +15,12 @@ import math import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdPhysics import isaaclab.sim.schemas as schemas +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.utils import find_global_fixed_joint_prim from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.string import to_camel_case diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index 59b2741e4ee..5bc085276fc 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -13,12 +13,12 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index ec178244e1b..a2480a8c146 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -13,12 +13,12 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdLux import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.string import to_camel_case diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index e95ee6e3724..b4086ae3d78 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -13,12 +13,12 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdPhysics, UsdShade import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index b2297255d97..f94c0542775 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -13,11 +13,11 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils @pytest.fixture diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index ac0cab828ad..ffcdf4a6fd7 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -13,11 +13,11 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.spawners.sensors.sensors import CUSTOM_FISHEYE_CAMERA_ATTRIBUTES, CUSTOM_PINHOLE_CAMERA_ATTRIBUTES from isaaclab.utils.string import to_camel_case diff --git a/source/isaaclab/test/sim/test_spawn_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index c889a4ab818..d98d57fe5c2 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -13,11 +13,11 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils @pytest.fixture diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 5edae7a79d6..542fa685ca2 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -13,11 +13,11 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR diff --git a/source/isaaclab/test/sim/test_stage_in_memory.py b/source/isaaclab/test/sim/test_stage_in_memory.py index d114185862a..0cd1f0bee6d 100644 --- a/source/isaaclab/test/sim/test_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_stage_in_memory.py @@ -13,7 +13,6 @@ """Rest everything follows.""" import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import omni import omni.physx import omni.usd @@ -23,6 +22,7 @@ from isaacsim.core.version import get_version import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.simulation_context import SimulationCfg, SimulationContext from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -59,7 +59,7 @@ def test_stage_in_memory_with_shapes(sim): # grab stage in memory and set as current stage via the with statement stage_in_memory = sim.get_initial_stage() - with sim_utils.use_stage(stage_in_memory): + with stage_utils.use_stage(stage_in_memory): # create cloned cone stage for i in range(num_clones): prim_utils.create_prim(f"/World/env_{i}", "Xform", translation=(i, i, 0)) @@ -88,7 +88,7 @@ def test_stage_in_memory_with_shapes(sim): cfg.func(prim_path_regex, cfg) # verify stage is in memory - assert sim_utils.is_current_stage_in_memory() + assert stage_utils.is_current_stage_in_memory() # verify prims exist in stage in memory prims = prim_utils.find_matching_prim_paths(prim_path_regex) @@ -96,7 +96,7 @@ def test_stage_in_memory_with_shapes(sim): # verify prims do not exist in context stage context_stage = omni.usd.get_context().get_stage() - with sim_utils.use_stage(context_stage): + with stage_utils.use_stage(context_stage): prims = prim_utils.find_matching_prim_paths(prim_path_regex) assert len(prims) != num_clones @@ -104,7 +104,7 @@ def test_stage_in_memory_with_shapes(sim): sim_utils.attach_stage_to_usd_context() # verify stage is no longer in memory - assert not sim_utils.is_current_stage_in_memory() + assert not stage_utils.is_current_stage_in_memory() # verify prims now exist in context stage prims = prim_utils.find_matching_prim_paths(prim_path_regex) @@ -128,7 +128,7 @@ def test_stage_in_memory_with_usds(sim): # grab stage in memory and set as current stage via the with statement stage_in_memory = sim.get_initial_stage() - with sim_utils.use_stage(stage_in_memory): + with stage_utils.use_stage(stage_in_memory): # create cloned robot stage for i in range(num_clones): prim_utils.create_prim(f"/World/env_{i}", "Xform", translation=(i, i, 0)) @@ -154,7 +154,7 @@ def test_stage_in_memory_with_usds(sim): cfg.func(prim_path_regex, cfg) # verify stage is in memory - assert sim_utils.is_current_stage_in_memory() + assert stage_utils.is_current_stage_in_memory() # verify prims exist in stage in memory prims = prim_utils.find_matching_prim_paths(prim_path_regex) @@ -162,7 +162,7 @@ def test_stage_in_memory_with_usds(sim): # verify prims do not exist in context stage context_stage = omni.usd.get_context().get_stage() - with sim_utils.use_stage(context_stage): + with stage_utils.use_stage(context_stage): prims = prim_utils.find_matching_prim_paths(prim_path_regex) assert len(prims) != num_clones @@ -170,7 +170,7 @@ def test_stage_in_memory_with_usds(sim): sim_utils.attach_stage_to_usd_context() # verify stage is no longer in memory - assert not sim_utils.is_current_stage_in_memory() + assert not stage_utils.is_current_stage_in_memory() # verify prims now exist in context stage prims = prim_utils.find_matching_prim_paths(prim_path_regex) @@ -191,7 +191,7 @@ def test_stage_in_memory_with_clone_in_fabric(sim): # grab stage in memory and set as current stage via the with statement stage_in_memory = sim.get_initial_stage() - with sim_utils.use_stage(stage_in_memory): + with stage_utils.use_stage(stage_in_memory): # set up paths base_env_path = "/World/envs" source_prim_path = f"{base_env_path}/env_0" @@ -218,7 +218,7 @@ def test_stage_in_memory_with_clone_in_fabric(sim): # verify prims do not exist in context stage context_stage = omni.usd.get_context().get_stage() - with sim_utils.use_stage(context_stage): + with stage_utils.use_stage(context_stage): prims = prim_utils.find_matching_prim_paths(prim_path_regex) assert len(prims) != num_clones @@ -226,10 +226,10 @@ def test_stage_in_memory_with_clone_in_fabric(sim): sim_utils.attach_stage_to_usd_context() # verify stage is no longer in memory - assert not sim_utils.is_current_stage_in_memory() + assert not stage_utils.is_current_stage_in_memory() # verify prims now exist in fabric stage using usdrt apis - stage_id = sim_utils.get_current_stage_id() + stage_id = stage_utils.get_current_stage_id() usdrt_stage = usdrt.Usd.Stage.Attach(stage_id) for i in range(num_clones): prim = usdrt_stage.GetPrimAtPath(f"/World/envs/env_{i}/Robot") diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index f238fd02408..522652ccd99 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -16,12 +16,12 @@ import os import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from isaacsim.core.api.simulation_context import SimulationContext from isaacsim.core.prims import Articulation from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg diff --git a/source/isaaclab/test/sim/test_utils.py b/source/isaaclab/test/sim/test_utils.py index a18e0534294..7559e2b4e75 100644 --- a/source/isaaclab/test/sim/test_utils.py +++ b/source/isaaclab/test/sim/test_utils.py @@ -16,11 +16,11 @@ import torch import isaacsim.core.utils.prims as prim_utils -import isaacsim.core.utils.stage as stage_utils import pytest from pxr import Sdf, Usd, UsdGeom, UsdPhysics import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index dd614082b8e..953bc04df3c 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -70,9 +70,10 @@ def get_camera_position(): tuple: (x, y, z) camera position or None if not available """ try: - import isaacsim.core.utils.stage as stage_utils from pxr import UsdGeom + import isaaclab.sim.utils.stage as stage_utils + stage = stage_utils.get_current_stage() if stage is not None: # Get the viewport camera prim diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py index 8e0aab5b0c7..0f33d65dc21 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py @@ -7,7 +7,6 @@ import torch -from isaacsim.core.utils.stage import get_current_stage from isaacsim.core.utils.torch.transformations import tf_combine, tf_inverse, tf_vector from pxr import UsdGeom @@ -17,6 +16,7 @@ from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_vision_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_vision_env.py index 42e8c4f03c4..13bc6a55328 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_vision_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_vision_env.py @@ -14,12 +14,11 @@ except ModuleNotFoundError: from pxr import Semantics -from isaacsim.core.utils.stage import get_current_stage - import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, RigidObject from isaaclab.scene import InteractiveSceneCfg from isaaclab.sensors import TiledCamera, TiledCameraCfg +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.utils import configclass from isaaclab.utils.math import quat_apply