diff --git a/isaaclab.sh b/isaaclab.sh
index c5cf66b95af..ef23b4cd0bc 100755
--- a/isaaclab.sh
+++ b/isaaclab.sh
@@ -348,6 +348,8 @@ while [[ $# -gt 0 ]]; do
# install the python packages in IsaacLab/source directory
echo "[INFO] Installing extensions inside the Isaac Lab repository..."
python_exe=$(extract_python_exe)
+ # install omni.client via packman helper
+ ${python_exe} "${ISAACLAB_PATH}/tools/installation/install_omni_client_packman.py"
# check if pytorch is installed and its version
# install pytorch with cuda 12.8 for blackwell support
if ${python_exe} -m pip list 2>/dev/null | grep -q "torch"; then
diff --git a/scripts/demos/cloner.py b/scripts/demos/cloner.py
new file mode 100644
index 00000000000..06cf46b5acd
--- /dev/null
+++ b/scripts/demos/cloner.py
@@ -0,0 +1,319 @@
+# 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
+
+"""This script demonstrates how to spawn multiple objects in multiple environments.
+
+.. code-block:: bash
+
+ # Usage
+ ./isaaclab.sh -p scripts/demos/multi_asset.py --num_envs 2048
+
+"""
+
+from __future__ import annotations
+
+"""Launch Isaac Sim Simulator first."""
+
+
+import argparse
+
+from isaaclab.app import AppLauncher
+
+# add argparse arguments
+parser = argparse.ArgumentParser(description="Demo on spawning different objects in multiple environments.")
+parser.add_argument("--num_envs", type=int, default=32, help="Number of environments to spawn.")
+parser.add_argument("--newton_visualizer", action="store_true", default=False, help="Enable Newton rendering.")
+# 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."""
+
+##
+# Pre-defined Configuration
+##
+import torch
+
+import isaaclab.sim as sim_utils
+from isaaclab.assets import ( # RigidObject,; RigidObjectCfg,; RigidObjectCollection,; RigidObjectCollectionCfg,
+ Articulation,
+ ArticulationCfg,
+ AssetBaseCfg,
+)
+from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
+from isaaclab.sim import SimulationContext
+from isaaclab.sim._impl.newton_manager_cfg import NewtonCfg
+from isaaclab.sim._impl.solvers_cfg import MJWarpSolverCfg
+from isaaclab.utils import Timer, configclass
+from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR
+
+from isaaclab_assets.robots.anymal import ANYDRIVE_3_LSTM_ACTUATOR_CFG # isort: skip
+
+
+##
+# Scene Configuration
+##
+
+
+@configclass
+class MultiObjectSceneCfg(InteractiveSceneCfg):
+ """Configuration for a multi-object scene."""
+
+ # ground plane
+ ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
+
+ # lights
+ dome_light = AssetBaseCfg(
+ prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
+ )
+
+ # rigid object
+ object: ArticulationCfg = ArticulationCfg(
+ prim_path="/World/envs/env_.*/Object",
+ spawn=sim_utils.UsdFileCfg(
+ usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd",
+ mass_props=sim_utils.MassPropertiesCfg(mass=25.0),
+ scale=(5.0, 5.0, 5.0),
+ rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ solver_position_iteration_count=4, solver_velocity_iteration_count=0
+ ),
+ collision_props=sim_utils.CollisionPropertiesCfg(),
+ ),
+ init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 2.0)),
+ actuators={},
+ articulation_root_prim_path="",
+ )
+
+ # # object collection
+ # object_collection: RigidObjectCollectionCfg = RigidObjectCollectionCfg(
+ # rigid_objects={
+ # "object_A": RigidObjectCfg(
+ # prim_path="/World/envs/env_.*/Object_A",
+ # spawn=sim_utils.SphereCfg(
+ # radius=0.1,
+ # visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
+ # rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ # solver_position_iteration_count=4, solver_velocity_iteration_count=0
+ # ),
+ # mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
+ # collision_props=sim_utils.CollisionPropertiesCfg(),
+ # ),
+ # init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, -0.5, 2.0)),
+ # ),
+ # "object_B": RigidObjectCfg(
+ # prim_path="/World/envs/env_.*/Object_B",
+ # spawn=sim_utils.CuboidCfg(
+ # size=(0.1, 0.1, 0.1),
+ # visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
+ # rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ # solver_position_iteration_count=4, solver_velocity_iteration_count=0
+ # ),
+ # mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
+ # collision_props=sim_utils.CollisionPropertiesCfg(),
+ # ),
+ # init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.5, 2.0)),
+ # ),
+ # "object_C": RigidObjectCfg(
+ # prim_path="/World/envs/env_.*/Object_C",
+ # spawn=sim_utils.ConeCfg(
+ # radius=0.1,
+ # height=0.3,
+ # visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
+ # rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ # solver_position_iteration_count=4, solver_velocity_iteration_count=0
+ # ),
+ # mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
+ # collision_props=sim_utils.CollisionPropertiesCfg(),
+ # ),
+ # init_state=RigidObjectCfg.InitialStateCfg(pos=(0.5, 0.0, 2.0)),
+ # ),
+ # }
+ # )
+
+ # # articulation
+ robot: ArticulationCfg = ArticulationCfg(
+ prim_path="/World/envs/env_.*/Robot",
+ spawn=sim_utils.UsdFileCfg(
+ usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd",
+ rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ disable_gravity=False,
+ retain_accelerations=False,
+ linear_damping=0.0,
+ angular_damping=0.0,
+ max_linear_velocity=1000.0,
+ max_angular_velocity=1000.0,
+ max_depenetration_velocity=1.0,
+ ),
+ articulation_props=sim_utils.ArticulationRootPropertiesCfg(
+ enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0
+ ),
+ activate_contact_sensors=True,
+ ),
+ init_state=ArticulationCfg.InitialStateCfg(
+ pos=(0.0, 0.0, 0.6),
+ joint_pos={
+ ".*HAA": 0.0, # all HAA
+ ".*F_HFE": 0.4, # both front HFE
+ ".*H_HFE": -0.4, # both hind HFE
+ ".*F_KFE": -0.8, # both front KFE
+ ".*H_KFE": 0.8, # both hind KFE
+ },
+ ),
+ actuators={"legs": ANYDRIVE_3_LSTM_ACTUATOR_CFG},
+ )
+
+ # articulation
+ # robot: ArticulationCfg = ArticulationCfg(
+ # prim_path="/World/envs/env_.*/Robot",
+ # spawn=sim_utils.MultiUsdFileCfg(
+ # usd_path=[
+ # f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd",
+ # f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd",
+ # ],
+ # random_choice=True,
+ # rigid_props=sim_utils.RigidBodyPropertiesCfg(
+ # disable_gravity=False,
+ # retain_accelerations=False,
+ # linear_damping=0.0,
+ # angular_damping=0.0,
+ # max_linear_velocity=1000.0,
+ # max_angular_velocity=1000.0,
+ # max_depenetration_velocity=1.0,
+ # ),
+ # articulation_props=sim_utils.ArticulationRootPropertiesCfg(
+ # enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0
+ # ),
+ # activate_contact_sensors=True,
+ # ),
+ # init_state=ArticulationCfg.InitialStateCfg(
+ # pos=(0.0, 0.0, 0.6),
+ # joint_pos={
+ # ".*HAA": 0.0, # all HAA
+ # ".*F_HFE": 0.4, # both front HFE
+ # ".*H_HFE": -0.4, # both hind HFE
+ # ".*F_KFE": -0.8, # both front KFE
+ # ".*H_KFE": 0.8, # both hind KFE
+ # },
+ # ),
+ # actuators={"legs": ANYDRIVE_3_LSTM_ACTUATOR_CFG},
+ # )
+
+
+##
+# Simulation Loop
+##
+
+
+def run_simulator(sim: SimulationContext, scene: InteractiveScene):
+ """Runs the simulation loop."""
+ # Extract scene entities
+ # note: we only do this here for readability.
+ rigid_object: Articulation | None = scene["object"] if "object" in scene.keys() else None
+ rigid_object_collection: Articulation | None = (
+ scene["object_collection"] if "object_collection" in scene.keys() else None
+ )
+ robot: Articulation | None = scene["robot"] if "robot" in scene.keys() else None
+ # Define simulation stepping
+ sim_dt = sim.get_physics_dt()
+ count = 0
+ # Simulation loop
+ while simulation_app.is_running():
+ # Reset
+ if count % 250 == 0:
+ # reset counter
+ count = 0
+ # reset the scene entities
+ # object
+ if rigid_object:
+ root_state = rigid_object.data.default_root_state.clone()
+ root_state[:, :3] += scene.env_origins + torch.rand_like(root_state[:, :3]) * 0.5 - 0.25
+ rigid_object.write_root_pose_to_sim(root_state[:, :7])
+ rigid_object.write_root_velocity_to_sim(root_state[:, 7:])
+ # object collection
+ if rigid_object_collection:
+ object_state = rigid_object_collection.data.default_object_state.clone()
+ object_state[..., :3] += (
+ scene.env_origins.unsqueeze(1) + torch.rand_like(root_state[:, :3]) * 0.5 - 0.25
+ )
+ rigid_object_collection.write_object_link_pose_to_sim(object_state[..., :7])
+ rigid_object_collection.write_object_com_velocity_to_sim(object_state[..., 7:])
+ # robot
+ if robot:
+ # -- root state
+ root_state = robot.data.default_root_state.clone()
+ root_state[:, :3] += scene.env_origins + torch.rand_like(root_state[:, :3]) * 0.5 - 0.25
+ robot.write_root_pose_to_sim(root_state[:, :7])
+ robot.write_root_velocity_to_sim(root_state[:, 7:])
+ # -- joint state
+ joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone()
+ robot.write_joint_state_to_sim(joint_pos, joint_vel)
+ # clear internal buffers
+ scene.reset()
+ print("[INFO]: Resetting scene state...")
+
+ # Apply action to robot
+ # robot.set_joint_position_target(robot.data.default_joint_pos)
+ # Write data to sim
+ scene.write_data_to_sim()
+ # Perform step
+ sim.step()
+ # Increment counter
+ count += 1
+ # Update buffers
+ scene.update(sim_dt)
+
+
+def main():
+ """Main function."""
+ # Load kit helper
+
+ newton_cfg = NewtonCfg(
+ solver_cfg=MJWarpSolverCfg(
+ njmax=300,
+ nconmax=25,
+ ls_iterations=15,
+ cone="elliptic",
+ impratio=100.0,
+ ls_parallel=True,
+ ),
+ num_substeps=1,
+ debug_mode=False,
+ )
+ sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, newton_cfg=newton_cfg)
+ sim_cfg.enable_newton_rendering = args_cli.newton_visualizer
+ sim = SimulationContext(sim_cfg)
+ # Set main camera
+ sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
+ # Design scene
+ scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=True)
+ with Timer("[INFO] Time to create scene: "):
+ scene = InteractiveScene(scene_cfg)
+
+ # with Timer("[INFO] Time to randomize scene: "):
+ # # DO YOUR OWN OTHER KIND OF RANDOMIZATION HERE!
+ # # Note: Just need to acquire the right attribute about the property you want to set
+ # # Here is an example on setting color randomly
+ # randomize_shape_color(scene_cfg.object.prim_path)
+
+ # Play the simulator
+ with Timer("[INFO] Time to start Simulation: "):
+ # The code `sim.reset()` is resetting a simulation or a simulation environment.
+ sim.reset()
+ # Now we are ready!
+ print("[INFO]: Setup complete...")
+ # Run the simulator
+ run_simulator(sim, scene)
+
+
+if __name__ == "__main__":
+ # run the main execution
+ main()
+ # close sim app
+ simulation_app.close()
diff --git a/source/isaaclab/isaaclab/app/__init__.py b/source/isaaclab/isaaclab/app/__init__.py
index 9e9b53b2f37..2c513d437f8 100644
--- a/source/isaaclab/isaaclab/app/__init__.py
+++ b/source/isaaclab/isaaclab/app/__init__.py
@@ -9,7 +9,9 @@
* Ability to launch the simulation app with different configurations
* Run tests with the simulation app
+* Settings manager for storing configuration in both Omniverse and standalone modes
"""
from .app_launcher import AppLauncher # noqa: F401, F403
+from .settings_manager import SettingsManager, get_settings_manager, initialize_carb_settings # noqa: F401, F403
diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py
index 01c915b0af0..31bd24d4282 100644
--- a/source/isaaclab/isaaclab/app/app_launcher.py
+++ b/source/isaaclab/isaaclab/app/app_launcher.py
@@ -21,10 +21,19 @@
import sys
from typing import Any, Literal
+# Import the settings manager for non-Omniverse mode
+from .settings_manager import get_settings_manager, initialize_carb_settings
+
+# Conditionally import SimulationApp only when needed (for omniverse visualizer)
+# This allows running Isaac Lab with Rerun/Newton visualizers without the full Omniverse stack
+_SIMULATION_APP_AVAILABLE = False
+_SimulationApp = None
+
with contextlib.suppress(ModuleNotFoundError):
import isaacsim # noqa: F401
+ from isaacsim import SimulationApp as _SimulationApp
-from isaacsim import SimulationApp
+ _SIMULATION_APP_AVAILABLE = True
# import logger
logger = logging.getLogger(__name__)
@@ -127,38 +136,72 @@ def __init__(self, launcher_args: argparse.Namespace | dict | None = None, **kwa
# Integrate env-vars and input keyword args into simulation app config
self._config_resolution(launcher_args)
- # Internal: Override SimulationApp._start_app method to apply patches after app has started.
- self.__patch_simulation_start_app(launcher_args)
-
- # Create SimulationApp, passing the resolved self._config to it for initialization
- self._create_app()
- # Load IsaacSim extensions
- self._load_extensions()
- # Hide the stop button in the toolbar
- self._hide_stop_button()
- # Set settings from the given rendering mode
- self._set_rendering_mode_settings(launcher_args)
- # Set animation recording settings
- self._set_animation_recording_settings(launcher_args)
-
- # Hide play button callback if the timeline is stopped
- import omni.timeline
-
- self._hide_play_button_callback = (
- omni.timeline.get_timeline_interface()
- .get_timeline_event_stream()
- .create_subscription_to_pop_by_type(
- int(omni.timeline.TimelineEventType.STOP), lambda e: self._hide_play_button(True)
+ # Determine if SimulationApp (Omniverse) is needed
+ # Only launch SimulationApp if:
+ # 1. Omniverse visualizer is explicitly requested OR
+ # 2. No specific visualizers are requested but livestreaming is enabled OR
+ # 3. No specific visualizers are requested and GUI is needed (not headless)
+ self._omniverse_required = self._check_if_omniverse_required()
+
+ # Get the global settings manager
+ self._settings_manager = get_settings_manager()
+
+ if self._omniverse_required:
+ if not _SIMULATION_APP_AVAILABLE:
+ raise RuntimeError(
+ "SimulationApp is required for the requested configuration but isaacsim module is not available. "
+ "Please ensure Isaac Sim is properly installed."
+ )
+
+ print("[INFO][AppLauncher]: Omniverse mode - Launching SimulationApp...")
+
+ # Internal: Override SimulationApp._start_app method to apply patches after app has started.
+ self.__patch_simulation_start_app(launcher_args)
+
+ # Create SimulationApp, passing the resolved self._config to it for initialization
+ self._create_app()
+
+ # Initialize carb.settings integration in the settings manager
+ initialize_carb_settings()
+
+ # Load IsaacSim extensions
+ self._load_extensions()
+ # Hide the stop button in the toolbar
+ self._hide_stop_button()
+ # Set settings from the given rendering mode
+ self._set_rendering_mode_settings(launcher_args)
+ # Set animation recording settings
+ self._set_animation_recording_settings(launcher_args)
+
+ # Hide play button callback if the timeline is stopped
+ import omni.timeline
+
+ self._hide_play_button_callback = (
+ omni.timeline.get_timeline_interface()
+ .get_timeline_event_stream()
+ .create_subscription_to_pop_by_type(
+ int(omni.timeline.TimelineEventType.STOP), lambda e: self._hide_play_button(True)
+ )
)
- )
- self._unhide_play_button_callback = (
- omni.timeline.get_timeline_interface()
- .get_timeline_event_stream()
- .create_subscription_to_pop_by_type(
- int(omni.timeline.TimelineEventType.PLAY), lambda e: self._hide_play_button(False)
+ self._unhide_play_button_callback = (
+ omni.timeline.get_timeline_interface()
+ .get_timeline_event_stream()
+ .create_subscription_to_pop_by_type(
+ int(omni.timeline.TimelineEventType.PLAY), lambda e: self._hide_play_button(False)
+ )
)
- )
+ else:
+ print(
+ "[INFO][AppLauncher]: Standalone mode - Running without SimulationApp (Rerun/Newton visualizers"
+ " only)..."
+ )
+ self._app = None
+ # Store settings in the standalone settings manager
+ self._store_settings_standalone()
+
# Set up signal handlers for graceful shutdown
+ # -- during keyboard interrupt (Ctrl+C)
+ signal.signal(signal.SIGINT, self._interrupt_signal_handle_callback)
# -- during explicit `kill` commands
signal.signal(signal.SIGTERM, self._abort_signal_handle_callback)
# -- during segfaults
@@ -170,12 +213,20 @@ def __init__(self, launcher_args: argparse.Namespace | dict | None = None, **kwa
"""
@property
- def app(self) -> SimulationApp:
- """The launched SimulationApp."""
- if self._app is not None:
- return self._app
+ def app(self) -> Any:
+ """The launched SimulationApp (or None if running in standalone mode).
+
+ Returns:
+ SimulationApp instance if Omniverse mode is active, None if running in standalone mode.
+ """
+ if self._omniverse_required:
+ if self._app is not None:
+ return self._app
+ else:
+ raise RuntimeError("The `AppLauncher.app` member cannot be retrieved until the class is initialized.")
else:
- raise RuntimeError("The `AppLauncher.app` member cannot be retrieved until the class is initialized.")
+ # Standalone mode - no SimulationApp
+ return None
@property
def visualizer(self) -> list[str] | None:
@@ -512,6 +563,56 @@ def _check_argparser_config_params(config: dict) -> None:
# Print out values which will be used
print(f"[INFO][AppLauncher]: The argument '{key}' will be used to configure the SimulationApp.")
+ def _check_if_omniverse_required(self) -> bool:
+ """Check if SimulationApp (Omniverse) needs to be launched.
+
+ TODO: this will also need to check RTX renderer and kit app renderer in the future.
+
+ Returns:
+ True if SimulationApp is required, False if can run in standalone mode.
+ """
+ # Omniverse is required if:
+ # 1. Omniverse visualizer is explicitly requested
+ # 2. Livestreaming is enabled (requires Omniverse)
+ # 3. Cameras are enabled (requires Omniverse for rendering)
+
+ # Omniverse visualizer explicitly requested
+ if self._visualizer is not None and "omniverse" in self._visualizer:
+ return True
+
+ # Livestreaming requires Omniverse
+ if self._livestream >= 1:
+ return True
+
+ # Cameras enabled requires Omniverse for RTX rendering
+ if self._enable_cameras:
+ return True
+
+ # Otherwise, we can run in standalone mode (headless with rerun/newton, or just headless)
+ # If no visualizer is specified and not headless, we still assume headless mode (standalone)
+ return False
+
+ def _store_settings_standalone(self):
+ """Store settings in the standalone settings manager (non-Omniverse mode).
+
+ This replicates the settings that would normally be stored via carb.settings.
+ """
+ # Store render settings
+ self._settings_manager.set_bool("/isaaclab/render/offscreen", self._offscreen_render)
+ self._settings_manager.set_bool("/isaaclab/render/active_viewport", getattr(self, "_render_viewport", False))
+ self._settings_manager.set_bool("/isaaclab/render/rtx_sensors", False)
+
+ # Store visualizer settings
+ if self._visualizer is not None:
+ self._settings_manager.set_string("/isaaclab/visualizer", ",".join(self._visualizer))
+ else:
+ self._settings_manager.set_string("/isaaclab/visualizer", "")
+
+ print("[INFO][AppLauncher]: Standalone settings stored:")
+ print(f" - visualizer: {self._visualizer}")
+ print(f" - offscreen_render: {self._offscreen_render}")
+ print(f" - headless: {self._headless}")
+
def _config_resolution(self, launcher_args: dict):
"""Resolve the input arguments and environment variables.
@@ -880,7 +981,7 @@ def _create_app(self):
if "--verbose" not in sys.argv and "--info" not in sys.argv:
sys.stdout = open(os.devnull, "w") # noqa: SIM115
# launch simulation app
- self._app = SimulationApp(self._sim_app_config, experience=self._sim_experience_file)
+ self._app = _SimulationApp(self._sim_app_config, experience=self._sim_experience_file)
# enable sys stdout and stderr
sys.stdout = sys.__stdout__
@@ -904,41 +1005,41 @@ def _rendering_enabled(self) -> bool:
def _load_extensions(self):
"""Load correct extensions based on AppLauncher's resolved config member variables."""
- # These have to be loaded after SimulationApp is initialized
- import carb
-
- # Retrieve carb settings for modification
- carb_settings_iface = carb.settings.get_settings()
+ # These have to be loaded after SimulationApp is initialized (if in Omniverse mode)
+ # In standalone mode, we just store settings
- # set carb setting to indicate Isaac Lab's offscreen_render pipeline should be enabled
+ # Store settings using the settings manager (works in both Omniverse and standalone mode)
+ # set setting to indicate Isaac Lab's offscreen_render pipeline should be enabled
# this flag is used by the SimulationContext class to enable the offscreen_render pipeline
# when the render() method is called.
- carb_settings_iface.set_bool("/isaaclab/render/offscreen", self._offscreen_render)
+ self._settings_manager.set_bool("/isaaclab/render/offscreen", self._offscreen_render)
- # set carb setting to indicate Isaac Lab's render_viewport pipeline should be enabled
+ # set setting to indicate Isaac Lab's render_viewport pipeline should be enabled
# this flag is used by the SimulationContext class to enable the render_viewport pipeline
# when the render() method is called.
- carb_settings_iface.set_bool("/isaaclab/render/active_viewport", self._render_viewport)
+ self._settings_manager.set_bool("/isaaclab/render/active_viewport", self._render_viewport)
- # set carb setting to indicate no RTX sensors are used
+ # set setting to indicate no RTX sensors are used
# this flag is set to True when an RTX-rendering related sensor is created
# for example: the `Camera` sensor class
- carb_settings_iface.set_bool("/isaaclab/render/rtx_sensors", False)
+ self._settings_manager.set_bool("/isaaclab/render/rtx_sensors", False)
- # set carb setting to store the visualizer backend(s) specified via command-line
+ # set setting to store the visualizer backend(s) specified via command-line
# this allows SimulationContext to filter visualizers based on the --visualizer flag
- # Store as comma-separated string for carb settings compatibility
+ # Store as comma-separated string for settings compatibility
if self._visualizer is not None:
- carb_settings_iface.set_string("/isaaclab/visualizer", ",".join(self._visualizer))
+ self._settings_manager.set_string("/isaaclab/visualizer", ",".join(self._visualizer))
else:
- carb_settings_iface.set_string("/isaaclab/visualizer", "")
+ self._settings_manager.set_string("/isaaclab/visualizer", "")
- # set fabric update flag to disable updating transforms when rendering is disabled
- carb_settings_iface.set_bool("/physics/fabricUpdateTransformations", self._rendering_enabled())
+ # Only set Omniverse-specific settings if running in Omniverse mode
+ if self._settings_manager.is_omniverse_mode:
+ # set fabric update flag to disable updating transforms when rendering is disabled
+ self._settings_manager.set_bool("/physics/fabricUpdateTransformations", self._rendering_enabled())
- # in theory, this should ensure that dt is consistent across time stepping, but this is not the case
- # for now, we use the custom loop runner from Isaac Sim to achieve this
- carb_settings_iface.set_bool("/app/player/useFixedTimeStepping", False)
+ # in theory, this should ensure that dt is consistent across time stepping, but this is not the case
+ # for now, we use the custom loop runner from Isaac Sim to achieve this
+ self._settings_manager.set_bool("/app/player/useFixedTimeStepping", False)
def _hide_stop_button(self):
"""Hide the stop button in the toolbar.
@@ -1003,10 +1104,11 @@ def _set_animation_recording_settings(self, launcher_args: dict) -> None:
def _interrupt_signal_handle_callback(self, signal, frame):
"""Handle the interrupt signal from the keyboard."""
- # close the app
- self._app.close()
- # raise the error for keyboard interrupt
- raise KeyboardInterrupt
+ # close the app (if running in Omniverse mode)
+ if self._app is not None:
+ self._app.close()
+ # exit gracefully without showing a traceback
+ sys.exit(0)
def _hide_play_button(self, flag):
"""Hide/Unhide the play button in the toolbar.
@@ -1027,8 +1129,9 @@ def _hide_play_button(self, flag):
def _abort_signal_handle_callback(self, signal, frame):
"""Handle the abort/segmentation/kill signals."""
- # close the app
- self._app.close()
+ # close the app (if running in Omniverse mode)
+ if self._app is not None:
+ self._app.close()
def __patch_simulation_start_app(self, launcher_args: dict):
if not launcher_args.get("enable_pinocchio", False):
@@ -1037,13 +1140,13 @@ def __patch_simulation_start_app(self, launcher_args: dict):
if launcher_args.get("disable_pinocchio_patch", False):
return
- original_start_app = SimulationApp._start_app
+ original_start_app = _SimulationApp._start_app
def _start_app_patch(sim_app_instance, *args, **kwargs):
original_start_app(sim_app_instance, *args, **kwargs)
self.__patch_pxr_gf_matrix4d(launcher_args)
- SimulationApp._start_app = _start_app_patch
+ _SimulationApp._start_app = _start_app_patch
def __patch_pxr_gf_matrix4d(self, launcher_args: dict):
import traceback
diff --git a/source/isaaclab/isaaclab/app/settings_manager.py b/source/isaaclab/isaaclab/app/settings_manager.py
new file mode 100644
index 00000000000..1a1e5f847bc
--- /dev/null
+++ b/source/isaaclab/isaaclab/app/settings_manager.py
@@ -0,0 +1,205 @@
+# 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
+
+"""Settings manager for Isaac Lab that works with or without Omniverse carb.settings.
+
+This module provides a unified settings interface that can work in two modes:
+1. Omniverse mode: Uses carb.settings when SimulationApp is launched
+2. Standalone mode: Uses pure Python dictionary when running without Omniverse
+
+This allows Isaac Lab to run visualizers like Rerun and Newton without requiring
+the full Omniverse/SimulationApp stack.
+"""
+
+import sys
+from typing import Any
+
+# Key for storing singleton in sys.modules to survive module reloads (e.g., from Hydra)
+_SINGLETON_KEY = "__isaaclab_settings_manager_singleton__"
+
+
+class SettingsManager:
+ """A settings manager that provides a carb.settings-like interface without requiring Omniverse.
+
+ This class can work in two modes:
+ - Standalone mode: Uses a Python dictionary to store settings
+ - Omniverse mode: Delegates to carb.settings when available
+
+ The interface is designed to be compatible with the carb.settings API.
+
+ This is implemented as a singleton to ensure only one instance exists across the application,
+ even when used in different execution contexts (e.g., Hydra). The singleton is stored in
+ sys.modules to survive module reloads.
+ """
+
+ def __new__(cls):
+ """Singleton pattern - always return the same instance, stored in sys.modules to survive reloads."""
+ # Check if instance exists in sys.modules (survives module reloads)
+ instance = sys.modules.get(_SINGLETON_KEY)
+
+ if instance is None:
+ instance = super().__new__(cls)
+ sys.modules[_SINGLETON_KEY] = instance
+ # Mark that this instance needs initialization
+ instance._needs_init = True
+
+ return instance
+
+ def __init__(self):
+ """Initialize the settings manager (only runs once due to singleton pattern)."""
+ # Check if this instance needs initialization
+ needs_init = getattr(self, "_needs_init", False)
+
+ if not needs_init:
+ return
+
+ self._standalone_settings: dict[str, Any] = {}
+ self._carb_settings = None
+ self._use_carb = False
+ self._needs_init = False
+
+ @classmethod
+ def instance(cls) -> "SettingsManager":
+ """Get the singleton instance of the settings manager.
+
+ Returns:
+ The singleton SettingsManager instance
+ """
+ # Get instance from sys.modules (survives module reloads)
+ instance = sys.modules.get(_SINGLETON_KEY)
+
+ if instance is None:
+ instance = cls()
+
+ return instance
+
+ def initialize_carb_settings(self):
+ """Initialize carb.settings if SimulationApp has been launched.
+
+ This should be called after SimulationApp is created to enable
+ Omniverse mode. If not called, the manager operates in standalone mode.
+ """
+ try:
+ import carb
+
+ self._carb_settings = carb.settings.get_settings()
+ self._use_carb = True
+ except (ImportError, AttributeError):
+ # carb not available or SimulationApp not launched - use standalone mode
+ self._use_carb = False
+
+ def set(self, path: str, value: Any) -> None:
+ """Set a setting value at the given path.
+
+ Args:
+ path: The settings path (e.g., "/isaaclab/render/offscreen")
+ value: The value to set
+ """
+ if self._use_carb and self._carb_settings is not None:
+ # Delegate to carb.settings
+ if isinstance(value, bool):
+ self._carb_settings.set_bool(path, value)
+ elif isinstance(value, int):
+ self._carb_settings.set_int(path, value)
+ elif isinstance(value, float):
+ self._carb_settings.set_float(path, value)
+ elif isinstance(value, str):
+ self._carb_settings.set_string(path, value)
+ else:
+ # For other types, try generic set
+ self._carb_settings.set(path, value)
+ else:
+ # Standalone mode - use dictionary
+ self._standalone_settings[path] = value
+
+ def get(self, path: str, default: Any = None) -> Any:
+ """Get a setting value at the given path.
+
+ Args:
+ path: The settings path (e.g., "/isaaclab/render/offscreen")
+ default: Default value to return if path doesn't exist
+
+ Returns:
+ The value at the path, or default if not found
+ """
+ if self._use_carb and self._carb_settings is not None:
+ # Delegate to carb.settings
+ value = self._carb_settings.get(path)
+ return value if value is not None else default
+ else:
+ # Standalone mode - use dictionary
+ return self._standalone_settings.get(path, default)
+
+ def set_bool(self, path: str, value: bool) -> None:
+ """Set a boolean setting value.
+
+ Args:
+ path: The settings path
+ value: The boolean value to set
+ """
+ self.set(path, value)
+
+ def set_int(self, path: str, value: int) -> None:
+ """Set an integer setting value.
+
+ Args:
+ path: The settings path
+ value: The integer value to set
+ """
+ self.set(path, value)
+
+ def set_float(self, path: str, value: float) -> None:
+ """Set a float setting value.
+
+ Args:
+ path: The settings path
+ value: The float value to set
+ """
+ self.set(path, value)
+
+ def set_string(self, path: str, value: str) -> None:
+ """Set a string setting value.
+
+ Args:
+ path: The settings path
+ value: The string value to set
+ """
+ self.set(path, value)
+
+ @property
+ def is_omniverse_mode(self) -> bool:
+ """Check if the settings manager is using carb.settings (Omniverse mode).
+
+ Returns:
+ True if using carb.settings, False if using standalone mode
+ """
+ return self._use_carb
+
+
+def get_settings_manager() -> SettingsManager:
+ """Get the global settings manager instance.
+
+ The SettingsManager is implemented as a singleton, so this function
+ always returns the same instance. The singleton is stored in sys.modules
+ to survive module reloads (e.g., from Hydra).
+
+ Returns:
+ The global SettingsManager instance
+ """
+ # Get instance from sys.modules (survives module reloads)
+ instance = sys.modules.get(_SINGLETON_KEY)
+ if instance is None:
+ instance = SettingsManager()
+ return instance
+
+
+def initialize_carb_settings():
+ """Initialize carb.settings integration for the global settings manager.
+
+ This should be called after SimulationApp is created to enable
+ Omniverse mode for the global settings manager.
+ """
+ manager = get_settings_manager()
+ manager.initialize_carb_settings()
diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation.py b/source/isaaclab/isaaclab/assets/articulation/articulation.py
index b9a45105a17..22cdda49256 100644
--- a/source/isaaclab/isaaclab/assets/articulation/articulation.py
+++ b/source/isaaclab/isaaclab/assets/articulation/articulation.py
@@ -15,7 +15,6 @@
from typing import TYPE_CHECKING, Literal
import warp as wp
-from isaacsim.core.simulation_manager import SimulationManager
from newton import JointMode, JointType, Model
from newton.selection import ArticulationView as NewtonArticulationView
from newton.solvers import SolverMuJoCo
@@ -1326,8 +1325,6 @@ def write_spatial_tendon_properties_to_sim(
"""
def _initialize_impl(self):
- # obtain global simulation view
- self._physics_sim_view = SimulationManager.get_physics_sim_view()
if self.cfg.articulation_root_prim_path is not None:
# The articulation root prim path is specified explicitly, so we can just use this.
diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py
index 617e810a980..d50797e0ae4 100644
--- a/source/isaaclab/isaaclab/assets/asset_base.py
+++ b/source/isaaclab/isaaclab/assets/asset_base.py
@@ -6,6 +6,7 @@
from __future__ import annotations
import builtins
+import contextlib
import inspect
import re
import torch
@@ -14,16 +15,13 @@
from collections.abc import Sequence
from typing import TYPE_CHECKING, Any
-import omni.kit.app
-import omni.timeline
-from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager
-
import isaaclab.sim as sim_utils
import isaaclab.sim.utils.prims as prim_utils
from isaaclab.sim import SimulationContext
from isaaclab.sim._impl.newton_manager import NewtonManager
from isaaclab.sim.utils.stage import get_current_stage
+
if TYPE_CHECKING:
from .asset_base_cfg import AssetBaseCfg
@@ -75,14 +73,8 @@ def __init__(self, cfg: AssetBaseCfg):
# get stage handle
self.stage = get_current_stage()
- # check if base asset path is valid
- # note: currently the spawner does not work if there is a regex pattern in the leaf
- # For example, if the prim path is "/World/Robot_[1,2]" since the spawner will not
- # know which prim to spawn. This is a limitation of the spawner and not the asset.
- asset_path = self.cfg.prim_path.split("/")[-1]
- asset_path_is_regex = re.match(r"^[a-zA-Z0-9/_]+$", asset_path) is None
# spawn the asset
- if self.cfg.spawn is not None and not asset_path_is_regex:
+ if self.cfg.spawn is not None:
self.cfg.spawn.func(
self.cfg.prim_path,
self.cfg.spawn,
@@ -107,7 +99,7 @@ def safe_callback(callback_name, event, obj_ref):
# note: use weakref on callbacks to ensure that this object can be deleted when its destructor is called.
# add callbacks for stage play/stop
obj_ref = weakref.proxy(self)
- timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
+ # timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
# the order is set to 10 which is arbitrary but should be lower priority than the default order of 0
# register timeline PLAY event callback (lower priority with order=10)
@@ -118,17 +110,17 @@ def safe_callback(callback_name, event, obj_ref):
# order=10,
# )
- # register timeline STOP event callback (lower priority with order=10)
- self._invalidate_initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type(
- int(omni.timeline.TimelineEventType.STOP),
- lambda event, obj_ref=obj_ref: safe_callback("_invalidate_initialize_callback", event, obj_ref),
- order=10,
- )
- # register prim deletion callback
- self._prim_deletion_callback_id = SimulationManager.register_callback(
- lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref),
- event=IsaacEvents.PRIM_DELETION,
- )
+ # # register timeline STOP event callback (lower priority with order=10)
+ # self._invalidate_initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type(
+ # int(omni.timeline.TimelineEventType.STOP),
+ # lambda event, obj_ref=obj_ref: safe_callback("_invalidate_initialize_callback", event, obj_ref),
+ # order=10,
+ # )
+ # # register prim deletion callback
+ # self._prim_deletion_callback_id = SimulationManager.register_callback(
+ # lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref),
+ # event=IsaacEvents.PRIM_DELETION,
+ # )
# add handle for debug visualization (this is set to a valid handle inside set_debug_vis)
self._debug_vis_handle = None
@@ -137,8 +129,10 @@ def safe_callback(callback_name, event, obj_ref):
def __del__(self):
"""Unsubscribe from the callbacks."""
- # clear events handles
- self._clear_callbacks()
+ # Suppress errors during Python shutdown
+ with contextlib.suppress(ImportError, AttributeError, TypeError):
+ # clear events handles
+ self._clear_callbacks()
"""
Properties
@@ -232,10 +226,13 @@ def set_debug_vis(self, debug_vis: bool) -> bool:
if debug_vis:
# create a subscriber for the post update event if it doesn't exist
if self._debug_vis_handle is None:
- app_interface = omni.kit.app.get_app_interface()
- self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop(
- lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event)
- )
+ with contextlib.suppress(ImportError):
+ import omni.kit.app
+
+ app_interface = omni.kit.app.get_app_interface()
+ self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop(
+ lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event)
+ )
else:
# remove the subscriber if it exists
if self._debug_vis_handle is not None:
@@ -308,8 +305,9 @@ def _initialize_callback(self, event):
"""
if not self._is_initialized:
# obtain simulation related information
- self._backend = SimulationManager.get_backend()
- self._device = SimulationManager.get_physics_sim_device()
+ # self._backend = SimulationManager.get_backend()
+ # self._device = SimulationManager.get_physics_sim_device()
+ self._device = SimulationContext.instance().device
# initialize the asset
try:
self._initialize_impl()
@@ -349,13 +347,16 @@ def _on_prim_deletion(self, prim_path: str) -> None:
def _clear_callbacks(self) -> None:
"""Clears the callbacks."""
- if self._prim_deletion_callback_id:
- SimulationManager.deregister_callback(self._prim_deletion_callback_id)
+ if getattr(self, "_prim_deletion_callback_id", None):
+ with contextlib.suppress(ImportError, NameError):
+ from isaacsim.core.simulation_manager import SimulationManager
+
+ SimulationManager.deregister_callback(self._prim_deletion_callback_id)
self._prim_deletion_callback_id = None
- if self._invalidate_initialize_handle:
+ if getattr(self, "_invalidate_initialize_handle", None):
self._invalidate_initialize_handle.unsubscribe()
self._invalidate_initialize_handle = None
# clear debug visualization
- if self._debug_vis_handle:
+ if getattr(self, "_debug_vis_handle", None):
self._debug_vis_handle.unsubscribe()
self._debug_vis_handle = None
diff --git a/source/isaaclab/isaaclab/cloner/__init__.py b/source/isaaclab/isaaclab/cloner/__init__.py
index 634fbcd3231..34518d57669 100644
--- a/source/isaaclab/isaaclab/cloner/__init__.py
+++ b/source/isaaclab/isaaclab/cloner/__init__.py
@@ -3,14 +3,6 @@
#
# SPDX-License-Identifier: BSD-3-Clause
-# SPDX-FileCopyrightText: Copyright (c) 2022-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
-# SPDX-License-Identifier: LicenseRef-NvidiaProprietary
-#
-# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
-# property and proprietary rights in and to this material, related
-# documentation and any modifications thereto. Any use, reproduction,
-# disclosure or distribution of this material and related documentation
-# without an express license agreement from NVIDIA CORPORATION or
-# its affiliates is strictly prohibited.
-from isaaclab.cloner.cloner import Cloner
-from isaaclab.cloner.grid_cloner import GridCloner
+from .cloner_cfg import TemplateCloneCfg
+from .cloner_strategies import *
+from .cloner_utils import *
diff --git a/source/isaaclab/isaaclab/cloner/cloner.py b/source/isaaclab/isaaclab/cloner/cloner.py
deleted file mode 100644
index 7ad669df16e..00000000000
--- a/source/isaaclab/isaaclab/cloner/cloner.py
+++ /dev/null
@@ -1,285 +0,0 @@
-# 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 logging
-
-# SPDX-FileCopyrightText: Copyright (c) 2022-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
-# SPDX-License-Identifier: LicenseRef-NvidiaProprietary
-#
-# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
-# property and proprietary rights in and to this material, related
-# documentation and any modifications thereto. Any use, reproduction,
-# disclosure or distribution of this material and related documentation
-# without an express license agreement from NVIDIA CORPORATION or
-# its affiliates is strictly prohibited.
-import numpy as np
-import torch
-
-import carb
-import carb.settings
-import omni.usd
-from pxr import Gf, Sdf, Usd, UsdGeom, Vt
-
-from isaaclab.utils.timer import Timer
-
-# import logger
-logger = logging.getLogger(__name__)
-
-
-class Cloner:
- """This class provides a set of simple APIs to make duplication of objects simple.
- Objects can be cloned using this class to create copies of the same object,
- placed at user-specified locations in the scene.
-
- Note that the cloning process is performed in a for-loop, so performance should
- be expected to follow linear scaling with an increase of clones.
- """
-
- def __init__(self, stage: Usd.Stage = None):
- """
- Args:
- stage (Usd.Stage): Usd stage where source prim and clones are added to.
- """
- self._base_env_path = None
- self._root_path = None
- self._stage = stage
- if stage is None:
- self._stage = omni.usd.get_context().get_stage()
-
- def define_base_env(self, base_env_path: str):
- """Creates a USD Scope at base_env_path. This is designed to be the parent that holds all clones.
-
- Args:
- base_env_path (str): Path to create the USD Scope at.
- """
-
- UsdGeom.Scope.Define(self._stage, base_env_path)
- self._base_env_path = base_env_path
-
- def generate_paths(self, root_path: str, num_paths: int):
- """Generates a list of paths under the root path specified.
-
- Args:
- root_path (str): Base path where new paths will be created under.
- num_paths (int): Number of paths to generate.
-
- Returns:
- paths (List[str]): A list of paths
- """
-
- self._root_path = root_path + "_"
- return [f"{root_path}_{i}" for i in range(num_paths)]
-
- @Timer(name="usd_clone", msg="Clone took:", enable=True, format="ms")
- def clone( # noqa: C901
- self,
- source_prim_path: str,
- prim_paths: list[str],
- positions: np.ndarray | torch.Tensor = None,
- orientations: np.ndarray | torch.Tensor = None,
- replicate_physics: bool = False,
- clone_in_fabric: bool = False,
- base_env_path: str = None,
- root_path: str = None,
- copy_from_source: bool = False,
- unregister_physics_replication: bool = False,
- enable_env_ids: bool = False,
- ):
- """Clones a source prim at user-specified destination paths.
- Clones will be placed at user-specified positions and orientations.
-
- Args:
- source_prim_path (str): Path of source object.
- prim_paths (List[str]): List of destination paths.
- positions (Union[np.ndarray, torch.Tensor]): An array containing target positions of clones. Dimension must equal length of prim_paths.
- Defaults to None. Clones will be placed at (0, 0, 0) if not specified.
- orientations (Union[np.ndarray, torch.Tensor]): An array containing target orientations of clones. Dimension must equal length of prim_paths.
- Defaults to None. Clones will have identity orientation (1, 0, 0, 0) if not specified.
- replicate_physics (bool): Uses omni.physics replication. This will replicate physics properties directly for paths beginning with root_path and skip physics parsing for anything under the base_env_path.
- clone_in_fabric (bool): Not supported in Newton. This is here for compatibility with IL 2.2.
- base_env_path (str): Path to namespace for all environments. Required if replicate_physics=True and define_base_env() not called.
- root_path (str): Prefix path for each environment. Required if replicate_physics=True and generate_paths() not called.
- copy_from_source: (bool): Setting this to False will inherit all clones from the source prim; any changes made to the source prim will be reflected in the clones.
- Setting this to True will make copies of the source prim when creating new clones; changes to the source prim will not be reflected in clones. Defaults to False. Note that setting this to True will take longer to execute.
- unregister_physics_replication (bool): Setting this to True will unregister the physics replicator on the current stage.
- enable_env_ids (bool): Setting this enables co-location of clones in physics with automatic filtering of collisions between clones.
- Raises:
- Exception: Raises exception if source prim path is not valid.
-
- """
- # check if inputs are valid
- if positions is not None:
- if len(positions) != len(prim_paths):
- raise ValueError("Dimension mismatch between positions and prim_paths!")
- # convert to numpy array
- if isinstance(positions, torch.Tensor):
- positions = positions.detach().cpu().numpy()
- elif not isinstance(positions, np.ndarray):
- positions = np.asarray(positions)
- # convert to pxr gf
- positions = Vt.Vec3fArray.FromNumpy(positions)
- if orientations is not None:
- if len(orientations) != len(prim_paths):
- raise ValueError("Dimension mismatch between orientations and prim_paths!")
- # convert to numpy array
- if isinstance(orientations, torch.Tensor):
- orientations = orientations.detach().cpu().numpy()
- elif not isinstance(orientations, np.ndarray):
- orientations = np.asarray(orientations)
- # convert to pxr gf -- wxyz to xyzw
- orientations = np.roll(orientations, -1, -1)
- orientations = Vt.QuatdArray.FromNumpy(orientations)
-
- # make sure source prim has valid xform properties
- source_prim = self._stage.GetPrimAtPath(source_prim_path)
- if not source_prim:
- raise Exception("Source prim does not exist")
- properties = source_prim.GetPropertyNames()
- xformable = UsdGeom.Xformable(source_prim)
- # get current position and orientation
- T_p_w = xformable.ComputeParentToWorldTransform(Usd.TimeCode.Default())
- T_l_w = xformable.ComputeLocalToWorldTransform(Usd.TimeCode.Default())
- T_l_p = Gf.Transform()
- T_l_p.SetMatrix(Gf.Matrix4d(np.matmul(T_l_w, np.linalg.inv(T_p_w)).tolist()))
- current_translation = T_l_p.GetTranslation()
- current_orientation = T_l_p.GetRotation().GetQuat()
- # get current scale
- current_scale = Gf.Vec3d(1, 1, 1)
- if "xformOp:scale" in properties:
- current_scale = Gf.Vec3d(source_prim.GetAttribute("xformOp:scale").Get())
-
- # remove all xform ops except for translate, orient, and scale
- properties_to_remove = [
- "xformOp:rotateX",
- "xformOp:rotateXZY",
- "xformOp:rotateY",
- "xformOp:rotateYXZ",
- "xformOp:rotateYZX",
- "xformOp:rotateZ",
- "xformOp:rotateZYX",
- "xformOp:rotateZXY",
- "xformOp:rotateXYZ",
- "xformOp:transform",
- "xformOp:scale",
- ]
- xformable.ClearXformOpOrder()
- for prop_name in properties:
- if prop_name in properties_to_remove:
- source_prim.RemoveProperty(prop_name)
-
- properties = source_prim.GetPropertyNames()
- # add xform ops if they don't exist
- if "xformOp:translate" not in properties:
- xform_op_translate = xformable.AddXformOp(
- UsdGeom.XformOp.TypeTranslate, UsdGeom.XformOp.PrecisionDouble, ""
- )
- else:
- xform_op_translate = UsdGeom.XformOp(source_prim.GetAttribute("xformOp:translate"))
- xform_op_translate.Set(current_translation)
-
- if "xformOp:orient" not in properties:
- xform_op_rot = xformable.AddXformOp(UsdGeom.XformOp.TypeOrient, UsdGeom.XformOp.PrecisionDouble, "")
- else:
- xform_op_rot = UsdGeom.XformOp(source_prim.GetAttribute("xformOp:orient"))
- if xform_op_rot.GetPrecision() == UsdGeom.XformOp.PrecisionFloat:
- current_orientation = Gf.Quatf(current_orientation)
- else:
- current_orientation = Gf.Quatd(current_orientation)
- xform_op_rot.Set(current_orientation)
-
- if "xformOp:scale" not in properties:
- xform_op_scale = xformable.AddXformOp(UsdGeom.XformOp.TypeScale, UsdGeom.XformOp.PrecisionDouble, "")
- else:
- xform_op_scale = UsdGeom.XformOp(source_prim.GetAttribute("xformOp:scale"))
- xform_op_scale.Set(current_scale)
- # set xform op order
- xformable.SetXformOpOrder([xform_op_translate, xform_op_rot, xform_op_scale])
-
- # set source actor transform
- if source_prim_path in prim_paths:
- idx = prim_paths.index(source_prim_path)
- prim = UsdGeom.Xform(self._stage.GetPrimAtPath(source_prim_path))
-
- if positions is not None:
- translation = positions[idx]
- else:
- translation = current_translation
-
- if orientations is not None:
- orientation = orientations[idx]
- else:
- orientation = current_orientation
-
- # overwrite translation and orientation to values specified
- prim.GetPrim().GetAttribute("xformOp:translate").Set(translation)
- prim.GetPrim().GetAttribute("xformOp:orient").Set(orientation)
-
- with Sdf.ChangeBlock():
- for i, prim_path in enumerate(prim_paths):
- if prim_path != source_prim_path:
- env_spec = Sdf.CreatePrimInLayer(self._stage.GetRootLayer(), prim_path)
-
- if copy_from_source:
- Sdf.CopySpec(env_spec.layer, Sdf.Path(source_prim_path), env_spec.layer, Sdf.Path(prim_path))
- else:
- env_spec.inheritPathList.Prepend(source_prim_path)
-
- if positions is not None:
- translation = positions[i] # use specified translation
- else:
- translation = current_translation # use the same translation as source
-
- if orientations is not None:
- orientation = orientations[i] # use specified orientation
- else:
- orientation = current_orientation # use the same orientation as source
-
- translate_spec = env_spec.GetAttributeAtPath(prim_path + ".xformOp:translate")
- if translate_spec is None:
- translate_spec = Sdf.AttributeSpec(env_spec, "xformOp:translate", Sdf.ValueTypeNames.Double3)
- translate_spec.default = translation
-
- orient_spec = env_spec.GetAttributeAtPath(prim_path + ".xformOp:orient")
- default_precision = carb.settings.get_settings().get_as_string(
- "app/primCreation/DefaultXformOpPrecision"
- )
- if orient_spec is None:
- if len(default_precision) > 0 and default_precision == "Float":
- orient_spec = Sdf.AttributeSpec(env_spec, "xformOp:orient", Sdf.ValueTypeNames.Quatf)
- orient_spec.default = Gf.Quatf(orientation)
- else:
- orient_spec = Sdf.AttributeSpec(env_spec, "xformOp:orient", Sdf.ValueTypeNames.Quatd)
- orient_spec.default = Gf.Quatd(orientation)
- elif orient_spec.default is not None and isinstance(orient_spec.default, Gf.Quatf):
- orient_spec.default = Gf.Quatf(orientation)
- else:
- orient_spec.default = Gf.Quatd(orientation)
-
- scale_spec = env_spec.GetAttributeAtPath(prim_path + ".xformOp:scale")
- if scale_spec is None:
- scale_spec = Sdf.AttributeSpec(env_spec, "xformOp:scale", Sdf.ValueTypeNames.Double3)
- scale_spec.default = current_scale
-
- op_order_spec = env_spec.GetAttributeAtPath(prim_path + ".xformOpOrder")
- if op_order_spec is None:
- op_order_spec = Sdf.AttributeSpec(
- env_spec, UsdGeom.Tokens.xformOpOrder, Sdf.ValueTypeNames.TokenArray
- )
- op_order_spec.default = Vt.TokenArray(["xformOp:translate", "xformOp:orient", "xformOp:scale"])
-
- def filter_collisions(
- self, physicsscene_path: str, collision_root_path: str, prim_paths: list[str], global_paths: list[str] = []
- ):
- """Filters collisions between clones. Clones will not collide with each other, but can collide with objects specified in global_paths.
-
- Args:
- physicsscene_path (str): Path to PhysicsScene object in stage.
- collision_root_path (str): Path to place collision groups under.
- prim_paths (List[str]): Paths of objects to filter out collision.
- global_paths (List[str]): Paths of objects to generate collision (e.g. ground plane).
-
- """
-
- return
diff --git a/source/isaaclab/isaaclab/cloner/cloner_cfg.py b/source/isaaclab/isaaclab/cloner/cloner_cfg.py
new file mode 100644
index 00000000000..ac1400b9f3d
--- /dev/null
+++ b/source/isaaclab/isaaclab/cloner/cloner_cfg.py
@@ -0,0 +1,84 @@
+# 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 __future__ import annotations
+
+from isaaclab.utils import configclass
+
+from .cloner_strategies import random
+from .cloner_utils import newton_replicate
+
+
+@configclass
+class TemplateCloneCfg:
+ """Configuration for template-based cloning.
+
+ This configuration is consumed by :func:`~isaaclab.scene.cloner.clone_from_template` to
+ replicate one or more "prototype" prims authored under a template root into multiple
+ per-environment destinations. It supports both USD-spec replication and PhysX replication
+ and allows choosing between random or round-robin prototype assignment across environments.
+
+ The cloning flow is:
+
+ 1. Discover prototypes under :attr:`template_root` whose base name starts with
+ :attr:`template_prototype_identifier` (for example, ``proto_asset_0``, ``proto_asset_1``).
+ 2. Build a per-prototype mapping to environments according to
+ :attr:`random_heterogeneous_cloning` (random) or modulo assignment (deterministic).
+ 3. Stamp the selected prototypes to destinations derived from :attr:`clone_regex`.
+ 4. Optionally perform PhysX replication for the same mapping.
+
+ Example
+ -------
+
+ .. code-block:: python
+
+ from isaaclab.cloner import TemplateCloneCfg, clone_from_template
+ from isaacsim.core.utils.stage import get_current_stage
+
+ stage = get_current_stage()
+ cfg = TemplateCloneCfg(
+ num_clones=128,
+ template_root="/World/template",
+ template_prototype_identifier="proto_asset",
+ clone_regex="/World/envs/env_.*",
+ clone_usd=True,
+ clone_physics=True,
+ random_heterogeneous_cloning=False, # use round-robin mapping
+ device="cpu",
+ )
+
+ clone_from_template(stage, num_clones=cfg.num_clones, template_clone_cfg=cfg)
+ """
+
+ template_root: str = "/World/template"
+ """Root path under which template prototypes are authored."""
+
+ template_prototype_identifier: str = "proto_asset"
+ """Name prefix used to identify prototype prims under :attr:`template_root`."""
+
+ clone_regex: str = "/World/envs/env_.*"
+ """Destination template for per-environment paths.
+
+ The substring ``".*"`` is replaced with ``"{}"`` internally and formatted with the
+ environment index (e.g., ``/World/envs/env_0``, ``/World/envs/env_1``).
+ """
+
+ clone_usd: bool = True
+ """Enable USD-spec replication to author cloned prims and optional transforms."""
+
+ clone_physics: bool = True
+ """Enable PhysX replication for the same mapping to speed up physics setup."""
+
+ physics_clone_fn: callable = newton_replicate
+ """Function used to perform physics replication. Default is :func:`newton_replicate`."""
+
+ clone_strategy: callable = random
+ """Function used to build prototype-to-environment mapping. Default is :func:`random`."""
+
+ device: str = "cpu"
+ """Torch device on which mapping buffers are allocated."""
+
+ clone_in_fabric: bool = False
+ """Enable/disable cloning in fabric for PhysX replication. Default is False."""
diff --git a/source/isaaclab/isaaclab/cloner/cloner_strategies.py b/source/isaaclab/isaaclab/cloner/cloner_strategies.py
new file mode 100644
index 00000000000..9be749cdb80
--- /dev/null
+++ b/source/isaaclab/isaaclab/cloner/cloner_strategies.py
@@ -0,0 +1,46 @@
+# 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 torch
+
+
+def random(combinations: torch.Tensor, num_clones: int, device: str) -> torch.Tensor:
+ """Randomly assign prototypes to environments.
+
+ Each environment is assigned a random prototype combination sampled uniformly from
+ :attr:`combinations`.
+
+ Args:
+ combinations: Tensor of shape (num_combos, num_prototypes) containing all possible
+ prototype combinations.
+ num_clones: Number of environments to assign combinations to.
+ device: Torch device on which the output tensor is allocated.
+
+ Returns:
+ Tensor of shape (num_clones, num_prototypes) containing the chosen prototype
+ combination for each environment.
+ """
+ chosen = combinations[torch.randint(len(combinations), (num_clones,), device=device)]
+ return chosen
+
+
+def sequential(combinations: torch.Tensor, num_clones: int, device: str) -> torch.Tensor:
+ """Deterministically assign prototypes to environments in round-robin fashion.
+
+ Each environment is assigned a prototype combination based on its index modulo the
+ number of available combinations.
+
+ Args:
+ combinations: Tensor of shape (num_combos, num_prototypes) containing all possible
+ prototype combinations.
+ num_clones: Number of environments to assign combinations to.
+ device: Torch device on which the output tensor is allocated.
+
+ Returns:
+ Tensor of shape (num_clones, num_prototypes) containing the chosen prototype
+ combination for each environment.
+ """
+ chosen = combinations[torch.arange(num_clones, device=device) % len(combinations)]
+ return chosen
diff --git a/source/isaaclab/isaaclab/cloner/cloner_utils.py b/source/isaaclab/isaaclab/cloner/cloner_utils.py
new file mode 100644
index 00000000000..34d33224280
--- /dev/null
+++ b/source/isaaclab/isaaclab/cloner/cloner_utils.py
@@ -0,0 +1,481 @@
+# 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 __future__ import annotations
+
+import itertools
+import math
+import torch
+from typing import TYPE_CHECKING
+
+import warp as wp
+from pxr import Gf, Sdf, Usd, UsdGeom, UsdUtils, Vt
+
+import isaaclab.sim as sim_utils
+from isaaclab.sim.utils import safe_set_attribute_on_usd_prim
+
+if TYPE_CHECKING:
+ from .cloner_cfg import TemplateCloneCfg
+
+
+def clone_from_template(stage: Usd.Stage, num_clones: int, template_clone_cfg: TemplateCloneCfg) -> None:
+ """Clone assets from a template root into per-environment destinations.
+
+ This utility discovers prototype prims under ``cfg.template_root`` whose names start with
+ ``cfg.template_prototype_identifier``, builds a per-prototype mapping across
+ ``num_clones`` environments (random or modulo), and then performs USD and/or PhysX replication
+ according to the flags in ``cfg``.
+
+ Args:
+ stage: The USD stage to author into.
+ num_clones: Number of environments to clone to (typically equals ``cfg.num_clones``).
+ template_clone_cfg: Configuration describing template location, destination pattern,
+ and replication/mapping behavior.
+ """
+ cfg: TemplateCloneCfg = template_clone_cfg
+ world_indices = torch.arange(num_clones, device=cfg.device)
+ clone_path_fmt = cfg.clone_regex.replace(".*", "{}")
+ prototype_id = cfg.template_prototype_identifier
+ prototypes = sim_utils.get_all_matching_child_prims(
+ cfg.template_root,
+ predicate=lambda prim: str(prim.GetPath()).split("/")[-1].startswith(prototype_id),
+ )
+ if len(prototypes) > 0:
+ prototype_root_set = {"/".join(str(prototype.GetPath()).split("/")[:-1]) for prototype in prototypes}
+ # discover prototypes per root then make a clone plan
+ src: list[list[str]] = []
+ dest: list[str] = []
+
+ for prototype_root in prototype_root_set:
+ protos = sim_utils.find_matching_prim_paths(f"{prototype_root}/.*")
+ protos = [proto for proto in protos if proto.split("/")[-1].startswith(prototype_id)]
+ src.append(protos)
+ dest.append(prototype_root.replace(cfg.template_root, clone_path_fmt))
+
+ src_paths, dest_paths, clone_masking = make_clone_plan(src, dest, num_clones, cfg.clone_strategy, cfg.device)
+
+ # Spawn the first instance of clones from prototypes, then deactivate the prototypes, those first instances
+ # will be served as sources for usd and physx replication.
+ proto_idx = clone_masking.to(torch.int32).argmax(dim=1)
+ proto_mask = torch.zeros_like(clone_masking)
+ proto_mask.scatter_(1, proto_idx.view(-1, 1).to(torch.long), clone_masking.any(dim=1, keepdim=True))
+ usd_replicate(stage, src_paths, dest_paths, world_indices, proto_mask)
+ stage.GetPrimAtPath(cfg.template_root).SetActive(False)
+
+ # If all prototypes map to env_0, clone whole env_0 to all envs; else clone per-object
+ if torch.all(proto_idx == 0):
+ # args: src_paths, dest_paths, env_ids, mask
+ replicate_args = [clone_path_fmt.format(0)], [clone_path_fmt], world_indices, clone_masking
+ get_pos = lambda path: stage.GetPrimAtPath(path).GetAttribute("xformOp:translate").Get() # noqa: E731
+ positions = torch.tensor([get_pos(clone_path_fmt.format(i)) for i in world_indices])
+ if cfg.clone_physics:
+ template_clone_cfg.physics_clone_fn(stage, *replicate_args, positions=positions)
+ if cfg.clone_usd:
+ # parse env_origins directly from clone_path
+ usd_replicate(stage, *replicate_args, positions=positions)
+
+ else:
+ selected_src = [tpl.format(int(idx)) for tpl, idx in zip(dest_paths, proto_idx.tolist())]
+ replicate_args = selected_src, dest_paths, world_indices, clone_masking
+ if cfg.clone_physics:
+ template_clone_cfg.physics_clone_fn(stage, *replicate_args)
+ if cfg.clone_usd:
+ usd_replicate(stage, *replicate_args)
+
+
+def make_clone_plan(
+ sources: list[list[str]],
+ destinations: list[str],
+ num_clones: int,
+ clone_strategy: callable,
+ device: str = "cpu",
+) -> tuple[list[str], list[str], torch.Tensor]:
+ """Construct a cloning plan mapping prototype prims to per-environment destinations.
+
+ The plan enumerates all combinations of prototypes, selects a combination per environment using ``clone_strategy``,
+ and builds a boolean masking matrix indicating which prototype populates each environment slot.
+
+ Args:
+ sources: Prototype prim paths grouped by asset type (e.g., [[robot_a, robot_b], [obj_x]]).
+ destinations: Destination path templates (one per group) with ``"{}"`` placeholder for env id.
+ num_clones: Number of environments to populate.
+ clone_strategy: Function that picks a prototype combo per environment; signature
+ ``clone_strategy(combos: Tensor, num_clones: int, device: str) -> Tensor[num_clones, num_groups]``.
+ device: Torch device for tensors in the plan. Defaults to ``"cpu"``.
+
+ Returns:
+ tuple: ``(src, dest, masking)`` where ``src`` and ``dest`` are flattened lists of prototype and
+ destination paths, and ``masking`` is a ``[num_src, num_clones]`` boolean tensor with True
+ when source ``src[i]`` is used for clone ``j``.
+ """
+ # 1) Flatten into src and dest lists
+ src = [p for group in sources for p in group]
+ dest = [dst for dst, group in zip(destinations, sources) for _ in group]
+ group_sizes = [len(group) for group in sources]
+
+ # 2) Enumerate all combinations of "one prototype per group"
+ # all_combos: list of tuples (g0_idx, g1_idx, ..., g_{G-1}_idx)
+ all_combos = list(itertools.product(*[range(s) for s in group_sizes]))
+ combos = torch.tensor(all_combos, dtype=torch.long, device=device)
+
+ # 3) Assign a combination to each environment
+ chosen = clone_strategy(combos, num_clones, device)
+
+ # 4) Build masking: [num_src, num_clones] boolean
+ # For each env, for each group, mark exactly one prototype row as True.
+ group_offsets = torch.tensor([0] + list(itertools.accumulate(group_sizes[:-1])), dtype=torch.long, device=device)
+ rows = (chosen + group_offsets).view(-1)
+ cols = torch.arange(num_clones, device=device).view(-1, 1).expand(-1, len(group_sizes)).reshape(-1)
+
+ masking = torch.zeros((sum(group_sizes), num_clones), dtype=torch.bool, device=device)
+ masking[rows, cols] = True
+ return src, dest, masking
+
+
+def usd_replicate(
+ stage: Usd.Stage,
+ sources: list[str],
+ destinations: list[str],
+ env_ids: torch.Tensor,
+ mask: torch.Tensor | None = None,
+ positions: torch.Tensor | None = None,
+ quaternions: torch.Tensor | None = None,
+) -> None:
+ """Replicate USD prims to per-environment destinations.
+
+ Copies each source prim spec to destination templates for selected environments
+ (``mask``). Optionally authors translate/orient from position/quaternion buffers.
+ Replication runs in path-depth order (parents before children) for robust composition.
+
+ Args:
+ stage: USD stage.
+ sources: Source prim paths.
+ destinations: Destination formattable templates with ``"{}"`` for env index.
+ env_ids: Environment indices.
+ mask: Optional per-source or shared mask. ``None`` selects all.
+ positions: Optional positions (``[E, 3]``) -> ``xformOp:translate``.
+ quaternions: Optional orientations (``[E, 4]``) in ``wxyz`` -> ``xformOp:orient``.
+
+ Returns:
+ None
+ """
+ rl = stage.GetRootLayer()
+
+ # Group replication by destination path depth so ancestors land before deeper paths.
+ # This avoids composition issues for nested or interdependent specs.
+ def dp_depth(template: str) -> int:
+ dp = template.format(0)
+ return Sdf.Path(dp).pathElementCount
+
+ order = sorted(range(len(sources)), key=lambda i: dp_depth(destinations[i]))
+
+ # Process in layers of equal depth, committing at each depth to stabilize composition
+ depth_to_indices: dict[int, list[int]] = {}
+ for i in order:
+ d = dp_depth(destinations[i])
+ depth_to_indices.setdefault(d, []).append(i)
+
+ for depth in sorted(depth_to_indices.keys()):
+ with Sdf.ChangeBlock():
+ for i in depth_to_indices[depth]:
+ src = sources[i]
+ tmpl = destinations[i]
+ # Select target environments for this source (supports None, [E], or [S, E])
+ target_envs = env_ids if mask is None else env_ids[mask[i]]
+ for wid in target_envs.tolist():
+ dp = tmpl.format(wid)
+ Sdf.CreatePrimInLayer(rl, dp)
+ Sdf.CopySpec(rl, Sdf.Path(src), rl, Sdf.Path(dp))
+
+ if positions is not None or quaternions is not None:
+ ps = rl.GetPrimAtPath(dp)
+ op_names = []
+ if positions is not None:
+ p = positions[wid]
+ t_attr = ps.GetAttributeAtPath(dp + ".xformOp:translate")
+ if t_attr is None:
+ t_attr = Sdf.AttributeSpec(ps, "xformOp:translate", Sdf.ValueTypeNames.Double3)
+ t_attr.default = Gf.Vec3d(float(p[0]), float(p[1]), float(p[2]))
+ op_names.append("xformOp:translate")
+ if quaternions is not None:
+ q = quaternions[wid]
+ o_attr = ps.GetAttributeAtPath(dp + ".xformOp:orient")
+ if o_attr is None:
+ o_attr = Sdf.AttributeSpec(ps, "xformOp:orient", Sdf.ValueTypeNames.Quatd)
+ o_attr.default = Gf.Quatd(float(q[0]), Gf.Vec3d(float(q[1]), float(q[2]), float(q[3])))
+ op_names.append("xformOp:orient")
+ # Only author xformOpOrder for the ops we actually authored
+ if op_names:
+ op_order = ps.GetAttributeAtPath(dp + ".xformOpOrder") or Sdf.AttributeSpec(
+ ps, UsdGeom.Tokens.xformOpOrder, Sdf.ValueTypeNames.TokenArray
+ )
+ op_order.default = Vt.TokenArray(op_names)
+
+
+def physx_replicate(
+ stage: Usd.Stage,
+ sources: list[str], # e.g. ["/World/Template/A", "/World/Template/B"]
+ destinations: list[str], # e.g. ["/World/envs/env_{}/Robot", "/World/envs/env_{}/Object"]
+ env_ids: torch.Tensor, # env_ids
+ mapping: torch.Tensor, # (num_sources, num_envs) bool; True -> place sources[i] into world=j
+ use_fabric: bool = False,
+) -> None:
+ """Replicate prims via PhysX replicator with per-row mapping.
+
+ Builds per-source destination lists from ``mapping`` and calls PhysX ``replicate``.
+ Rows covering all environments use ``useEnvIds=True``; partial rows use ``False``.
+ The replicator is registered for the call and then unregistered.
+
+ Args:
+ stage: USD stage.
+ sources: Source prim paths (``S``).
+ destinations: Destination templates (``S``) with ``"{}"`` for env index.
+ env_ids: Environment indices (``[E]``).
+ mapping: Bool/int mask (``[S, E]``) selecting envs per source.
+ use_fabric: Use Fabric for replication.
+
+ Returns:
+ None
+ """
+ from omni.physx import get_physx_replicator_interface
+
+ stage_id = UsdUtils.StageCache.Get().Insert(stage).ToLongInt()
+ current_worlds: list[int] = []
+ current_template: str = ""
+ num_envs = mapping.size(1)
+
+ def attach_fn(_stage_id: int):
+ return ["/World/envs", *sources]
+
+ def rename_fn(_replicate_path: str, i: int):
+ return current_template.format(current_worlds[i])
+
+ def attach_end_fn(_stage_id: int):
+ nonlocal current_template
+ rep = get_physx_replicator_interface()
+ for i, src in enumerate(sources):
+ current_worlds[:] = env_ids[mapping[i]].tolist()
+ current_template = destinations[i]
+ rep.replicate(
+ _stage_id,
+ src,
+ len(current_worlds),
+ useEnvIds=len(current_worlds) == num_envs,
+ useFabricForReplication=use_fabric,
+ )
+ # unregister only AFTER all replicate() calls completed
+ rep.unregister_replicator(_stage_id)
+
+ get_physx_replicator_interface().register_replicator(stage_id, attach_fn, attach_end_fn, rename_fn)
+
+
+def newton_replicate(
+ stage: Usd.Stage,
+ sources: list[str],
+ destinations: list[str],
+ env_ids: torch.Tensor,
+ mapping: torch.Tensor,
+ positions: torch.Tensor | None = None,
+ quaternions: torch.Tensor | None = None,
+ up_axis: str = "Z",
+ simplify_meshes: bool = True,
+):
+ """Replicate prims into a Newton ``ModelBuilder`` using a per-source mapping."""
+ from newton import ModelBuilder
+
+ from isaaclab.sim._impl.newton_manager import NewtonManager
+
+ if positions is None:
+ positions = torch.zeros((mapping.size(1), 3), device=mapping.device, dtype=torch.float32)
+ if quaternions is None:
+ quaternions = torch.zeros((mapping.size(1), 4), device=mapping.device, dtype=torch.float32)
+ quaternions[:, 3] = 1.0
+
+ # load empty stage
+ builder = ModelBuilder(up_axis=up_axis)
+ stage_info = builder.add_usd(stage, ignore_paths=["/World/envs"] + sources, load_non_physics_prims=False)
+
+ # build a prototype for each source
+ protos: dict[str, ModelBuilder] = {}
+ for src_path in sources:
+ p = ModelBuilder(up_axis=up_axis)
+ p.add_usd(stage, root_path=src_path, load_non_physics_prims=False)
+ if simplify_meshes:
+ p.approximate_meshes("convex_hull")
+ protos[src_path] = p
+
+ # add by world, then by active sources in that world (column-wise)
+ for col, env_id in enumerate(env_ids.tolist()):
+ for row in torch.nonzero(mapping[:, col], as_tuple=True)[0].tolist():
+ builder.add_builder(
+ protos[sources[row]],
+ xform=wp.transform(positions[col], quaternions[col]),
+ world=int(env_id),
+ )
+
+ # per-source, per-world renaming (strict prefix swap), compact style preserved
+ for i, src_path in enumerate(sources):
+ src_prefix_len = len(src_path.rstrip("/"))
+ swap = lambda name, new_root: new_root + name[src_prefix_len:] # noqa: E731
+ world_cols = torch.nonzero(mapping[i], as_tuple=True)[0].tolist()
+ world_roots = {int(env_ids[c]): destinations[i].format(int(env_ids[c])) for c in world_cols}
+
+ for t in ("body", "joint", "shape", "articulation"):
+ keys, worlds_arr = getattr(builder, f"{t}_key"), getattr(builder, f"{t}_world")
+ for k, w in enumerate(worlds_arr):
+ if w in world_roots and keys[k].startswith(src_path):
+ keys[k] = swap(keys[k], world_roots[w])
+
+ NewtonManager.set_builder(builder)
+ NewtonManager._num_envs = mapping.size(1)
+ return builder, stage_info
+
+
+def filter_collisions(
+ stage: Usd.Stage,
+ physicsscene_path: str,
+ collision_root_path: str,
+ prim_paths: list[str],
+ global_paths: list[str] = [],
+) -> None:
+ """Create inverted collision groups for clones.
+
+ Creates one PhysicsCollisionGroup per prim under ``collision_root_path``, enabling
+ inverted filtering so clones don't collide across groups. Optionally adds a global
+ group that collides with all.
+
+ Args:
+ stage: USD stage.
+ physicsscene_path: Path to PhysicsScene prim.
+ collision_root_path: Root scope for collision groups.
+ prim_paths: Per-clone prim paths.
+ global_paths: Optional global-collider paths.
+
+ Returns:
+ None
+ """
+ # Invert collision group filters for more efficient cross-environment filtering
+ safe_set_attribute_on_usd_prim(
+ stage.GetPrimAtPath(physicsscene_path), "physxScene:invertCollisionGroupFilter", value=True, camel_case=False
+ )
+
+ # Make sure we create the collision_scope in the RootLayer since the edit target may be a live layer in the case of Live Sync.
+ with Usd.EditContext(stage, Usd.EditTarget(stage.GetRootLayer())):
+ UsdGeom.Scope.Define(stage, collision_root_path)
+
+ with Sdf.ChangeBlock():
+ if len(global_paths) > 0:
+ global_collision_group_path = collision_root_path + "/global_group"
+ # add collision group prim
+ global_collision_group = Sdf.PrimSpec(
+ stage.GetRootLayer().GetPrimAtPath(collision_root_path),
+ "global_group",
+ Sdf.SpecifierDef,
+ "PhysicsCollisionGroup",
+ )
+ # prepend collision API schema
+ global_collision_group.SetInfo(Usd.Tokens.apiSchemas, Sdf.TokenListOp.Create({"CollectionAPI:colliders"}))
+
+ # expansion rule
+ expansion_rule = Sdf.AttributeSpec(
+ global_collision_group,
+ "collection:colliders:expansionRule",
+ Sdf.ValueTypeNames.Token,
+ Sdf.VariabilityUniform,
+ )
+ expansion_rule.default = "expandPrims"
+
+ # includes rel
+ global_includes_rel = Sdf.RelationshipSpec(global_collision_group, "collection:colliders:includes", False)
+ for global_path in global_paths:
+ global_includes_rel.targetPathList.Append(global_path)
+
+ # filteredGroups rel
+ global_filtered_groups = Sdf.RelationshipSpec(global_collision_group, "physics:filteredGroups", False)
+ # We are using inverted collision group filtering, which means objects by default don't collide across
+ # groups. We need to add this group as a filtered group, so that objects within this group collide with
+ # each other.
+ global_filtered_groups.targetPathList.Append(global_collision_group_path)
+
+ # set collision groups and filters
+ for i, prim_path in enumerate(prim_paths):
+ collision_group_path = collision_root_path + f"/group{i}"
+ # add collision group prim
+ collision_group = Sdf.PrimSpec(
+ stage.GetRootLayer().GetPrimAtPath(collision_root_path),
+ f"group{i}",
+ Sdf.SpecifierDef,
+ "PhysicsCollisionGroup",
+ )
+ # prepend collision API schema
+ collision_group.SetInfo(Usd.Tokens.apiSchemas, Sdf.TokenListOp.Create({"CollectionAPI:colliders"}))
+
+ # expansion rule
+ expansion_rule = Sdf.AttributeSpec(
+ collision_group,
+ "collection:colliders:expansionRule",
+ Sdf.ValueTypeNames.Token,
+ Sdf.VariabilityUniform,
+ )
+ expansion_rule.default = "expandPrims"
+
+ # includes rel
+ includes_rel = Sdf.RelationshipSpec(collision_group, "collection:colliders:includes", False)
+ includes_rel.targetPathList.Append(prim_path)
+
+ # filteredGroups rel
+ filtered_groups = Sdf.RelationshipSpec(collision_group, "physics:filteredGroups", False)
+ # We are using inverted collision group filtering, which means objects by default don't collide across
+ # groups. We need to add this group as a filtered group, so that objects within this group collide with
+ # each other.
+ filtered_groups.targetPathList.Append(collision_group_path)
+ if len(global_paths) > 0:
+ filtered_groups.targetPathList.Append(global_collision_group_path)
+ global_filtered_groups.targetPathList.Append(collision_group_path)
+
+
+def grid_transforms(N: int, spacing: float = 1.0, up_axis: str = "z", device="cpu"):
+ """Create a centered grid of transforms for ``N`` instances.
+
+ Computes ``(x, y)`` coordinates in a roughly square grid centered at the origin
+ with the provided spacing, places the third coordinate according to ``up_axis``,
+ and returns identity orientations (``wxyz``) for each instance.
+
+ Args:
+ N: Number of instances.
+ spacing: Distance between neighboring grid positions.
+ up_axis: Up axis for positions ("z", "y", or "x").
+ device: Torch device for returned tensors.
+
+ Returns:
+ A tuple ``(pos, ori)`` where:
+ - ``pos`` is a tensor of shape ``(N, 3)`` with positions.
+ - ``ori`` is a tensor of shape ``(N, 4)`` with identity quaternions in ``(w, x, y, z)``.
+ """
+ # rows/cols
+ rows = int(math.ceil(math.sqrt(N)))
+ cols = int(math.ceil(N / rows))
+
+ idx = torch.arange(N, device=device)
+ r = torch.div(idx, cols, rounding_mode="floor")
+ c = idx % cols
+
+ # centered grid coords
+ x = (c - (cols - 1) * 0.5) * spacing
+ y = ((rows - 1) * 0.5 - r) * spacing
+
+ # place on plane based on up_axis
+ z0 = torch.zeros_like(x)
+ if up_axis.lower() == "z":
+ pos = torch.stack([x, y, z0], dim=1)
+ elif up_axis.lower() == "y":
+ pos = torch.stack([x, z0, y], dim=1)
+ else: # up_axis == "x"
+ pos = torch.stack([z0, x, y], dim=1)
+
+ # identity orientations (w,x,y,z)
+ ori = torch.zeros((N, 4), device=device)
+ ori[:, 0] = 1.0
+ return pos, ori
diff --git a/source/isaaclab/isaaclab/cloner/grid_cloner.py b/source/isaaclab/isaaclab/cloner/grid_cloner.py
deleted file mode 100644
index a7feb6842a6..00000000000
--- a/source/isaaclab/isaaclab/cloner/grid_cloner.py
+++ /dev/null
@@ -1,198 +0,0 @@
-# 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
-
-# SPDX-FileCopyrightText: Copyright (c) 2022-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
-# SPDX-License-Identifier: LicenseRef-NvidiaProprietary
-#
-# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
-# property and proprietary rights in and to this material, related
-# documentation and any modifications thereto. Any use, reproduction,
-# disclosure or distribution of this material and related documentation
-# without an express license agreement from NVIDIA CORPORATION or
-# its affiliates is strictly prohibited.
-import numpy as np
-import torch
-
-import omni.usd
-from pxr import Gf, Usd, UsdGeom
-
-from isaaclab.cloner import Cloner
-from isaaclab.cloner.utils import replicate_environment
-from isaaclab.sim._impl.newton_manager import NewtonManager
-from isaaclab.utils.timer import Timer
-
-
-class GridCloner(Cloner):
- """This is a specialized Cloner class that will automatically generate clones in a grid fashion."""
-
- def __init__(self, spacing: float, num_per_row: int = -1, stage: Usd.Stage = None):
- """
- Args:
- spacing (float): Spacing between clones.
- num_per_row (int): Number of clones to place in a row. Defaults to sqrt(num_clones).
- stage (Usd.Stage): Usd stage where source prim and clones are added to.
- """
- self._spacing = spacing
- self._num_per_row = num_per_row
-
- self._positions = None
- self._orientations = None
-
- Cloner.__init__(self, stage)
-
- def get_clone_transforms(
- self,
- num_clones: int,
- position_offsets: np.ndarray = None,
- orientation_offsets: np.ndarray = None,
- ):
- """Computes the positions and orientations of clones in a grid.
-
- Args:
- num_clones (int): Number of clones.
- position_offsets (np.ndarray): Positions to be applied as local translations on top of computed clone position.
- position_offsets (np.ndarray | torch.Tensor): Positions to be applied as local translations on top of computed clone position.
- Defaults to None, no offset will be applied.
- orientation_offsets (np.ndarray | torch.Tensor): Orientations to be applied as local rotations for each clone.
- Defaults to None, no offset will be applied.
- Returns:
- positions (List): Computed positions of all clones.
- orientations (List): Computed orientations of all clones.
- """
- # check if inputs are valid
- if position_offsets is not None:
- if len(position_offsets) != num_clones:
- raise ValueError("Dimension mismatch between position_offsets and prim_paths!")
- # convert to numpy array
- if isinstance(position_offsets, torch.Tensor):
- position_offsets = position_offsets.detach().cpu().numpy()
- elif not isinstance(position_offsets, np.ndarray):
- position_offsets = np.asarray(position_offsets)
- if orientation_offsets is not None:
- if len(orientation_offsets) != num_clones:
- raise ValueError("Dimension mismatch between orientation_offsets and prim_paths!")
- # convert to numpy array
- if isinstance(orientation_offsets, torch.Tensor):
- orientation_offsets = orientation_offsets.detach().cpu().numpy()
- elif not isinstance(orientation_offsets, np.ndarray):
- orientation_offsets = np.asarray(orientation_offsets)
-
- if self._positions is not None and self._orientations is not None:
- return self._positions, self._orientations
-
- self._num_per_row = int(np.sqrt(num_clones)) if self._num_per_row == -1 else self._num_per_row
- num_rows = np.ceil(num_clones / self._num_per_row)
- num_cols = np.ceil(num_clones / num_rows)
-
- row_offset = 0.5 * self._spacing * (num_rows - 1)
- col_offset = 0.5 * self._spacing * (num_cols - 1)
-
- positions = []
- orientations = []
-
- for i in range(num_clones):
- # compute transform
- row = i // num_cols
- col = i % num_cols
- y = row_offset - row * self._spacing
- x = col * self._spacing - col_offset
-
- up_axis = UsdGeom.GetStageUpAxis(self._stage)
- position = [y, x, 0] if up_axis == UsdGeom.Tokens.z else [x, 0, y]
- orientation = Gf.Quatd.GetIdentity()
-
- if position_offsets is not None:
- translation = position_offsets[i] + position
- else:
- translation = position
-
- if orientation_offsets is not None:
- orientation = (
- Gf.Quatd(orientation_offsets[i][0].item(), Gf.Vec3d(orientation_offsets[i][1:].tolist()))
- * orientation
- )
-
- orientation = [
- orientation.GetReal(),
- orientation.GetImaginary()[0],
- orientation.GetImaginary()[1],
- orientation.GetImaginary()[2],
- ]
-
- positions.append(translation)
- orientations.append(orientation)
-
- self._positions = positions
- self._orientations = orientations
-
- return positions, orientations
-
- @Timer(name="newton_clone", msg="Clone took:", enable=True, format="ms")
- def clone(
- self,
- source_prim_path: str,
- prim_paths: list[str],
- position_offsets: np.ndarray = None,
- orientation_offsets: np.ndarray = None,
- replicate_physics: bool = False,
- base_env_path: str = None,
- clone_in_fabric: bool = False,
- root_path: str = None,
- copy_from_source: bool = False,
- enable_env_ids: bool = False,
- spawn_offset: tuple[float] = (0.0, 0.0, 0.0),
- ):
- """Creates clones in a grid fashion. Positions of clones are computed automatically.
-
- Args:
- source_prim_path (str): Path of source object.
- prim_paths (List[str]): List of destination paths.
- position_offsets (np.ndarray): Positions to be applied as local translations on top of computed clone position.
- Defaults to None, no offset will be applied.
- orientation_offsets (np.ndarray): Orientations to be applied as local rotations for each clone.
- Defaults to None, no offset will be applied.
- replicate_physics (bool): Uses omni.physics replication. This will replicate physics properties directly for paths beginning with root_path and skip physics parsing for anything under the base_env_path.
- base_env_path (str): Path to namespace for all environments. Required if replicate_physics=True and define_base_env() not called.
- clone_in_fabric (bool): Not supported in Newton. This is here for compatibility with IL 2.2.
- root_path (str): Prefix path for each environment. Required if replicate_physics=True and generate_paths() not called.
- copy_from_source: (bool): Setting this to False will inherit all clones from the source prim; any changes made to the source prim will be reflected in the clones.
- Setting this to True will make copies of the source prim when creating new clones; changes to the source prim will not be reflected in clones. Defaults to False. Note that setting this to True will take longer to execute.
- enable_env_ids (bool): Setting this enables co-location of clones in physics with automatic filtering of collisions between clones.
- Returns:
- positions (List): Computed positions of all clones.
- """
-
- num_clones = len(prim_paths)
- NewtonManager._num_envs = num_clones
-
- positions, orientations = self.get_clone_transforms(num_clones, position_offsets, orientation_offsets)
- if replicate_physics:
- clone_base_path = self._root_path if root_path is None else root_path
- builder, stage_info = replicate_environment(
- omni.usd.get_context().get_stage(),
- source_prim_path,
- clone_base_path + "{}",
- positions,
- orientations,
- spawn_offset=spawn_offset,
- simplify_meshes=True,
- collapse_fixed_joints=False,
- joint_ordering="dfs",
- joint_drive_gains_scaling=1.0,
- )
- NewtonManager.set_builder(builder)
- if not NewtonManager._clone_physics_only:
- super().clone(
- source_prim_path=source_prim_path,
- prim_paths=prim_paths,
- positions=positions,
- orientations=orientations,
- replicate_physics=replicate_physics,
- base_env_path=base_env_path,
- root_path=root_path,
- copy_from_source=copy_from_source,
- enable_env_ids=enable_env_ids,
- )
- return positions
diff --git a/source/isaaclab/isaaclab/cloner/utils.py b/source/isaaclab/isaaclab/cloner/utils.py
deleted file mode 100644
index 88892b6a70f..00000000000
--- a/source/isaaclab/isaaclab/cloner/utils.py
+++ /dev/null
@@ -1,151 +0,0 @@
-# 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 numpy as np
-from typing import Any
-
-import warp as wp
-from newton import AxisType, ModelBuilder
-from pxr import Usd
-
-from isaaclab.utils.timer import Timer
-
-
-@Timer(name="replicate_environment", msg="Replicate environment took:", enable=True, format="ms")
-def replicate_environment(
- source,
- prototype_path: str,
- path_pattern: str,
- positions: np.ndarray,
- orientations: np.ndarray,
- up_axis: AxisType = "Z",
- simplify_meshes: bool = True,
- spawn_offset: tuple[float] = (0.0, 0.0, 20.0),
- **usd_kwargs,
-) -> tuple[ModelBuilder, dict[str:Any]]:
- """
- Replicates a prototype USD environment in Newton.
-
- Args:
- source (str | pxr.UsdStage): The file path to the USD file, or an existing USD stage instance.
- prototype_path (str): The USD path where the prototype env is defined, e.g., "/World/envs/env_0".
- path_pattern (str): The USD path pattern for replicated envs, e.g., "/World/envs/env_{}".
- num_envs (int): Number of replicas to create.
- env_spacing (tuple[float]): Environment spacing vector.
- up_axis (AxisType): The desired up-vector (should match the USD stage).
- simplify_meshes (bool): If True, simplify the meshes to reduce the number of triangles. This is useful when
- meshes with complex geometry are used as collision meshes.
- spawn_offset (tuple[float]): The offset to apply to the spawned environments.
- **usd_kwargs: Keyword arguments to pass to the USD importer (see `newton.utils.parse_usd()`).
-
- Returns:
- (ModelBuilder, dict): The resulting ModelBuilder containing all replicated environments and a dictionary with USD stage information.
- """
-
- with Timer(name="newton_env_builder", msg="Env Builder took:", enable=True, format="ms"):
- builder = ModelBuilder(up_axis=up_axis)
-
- stage_info = builder.add_usd(
- source,
- ignore_paths=[prototype_path],
- **usd_kwargs,
- )
-
- # up_axis sanity check
- stage_up_axis = stage_info.get("up_axis")
- if isinstance(stage_up_axis, str) and stage_up_axis.upper() != up_axis.upper():
- print(f"WARNING: up_axis '{up_axis}' does not match USD stage up_axis '{stage_up_axis}'")
-
- with Timer(name="newton_prototype_builder", msg="Prototype Builder took:", enable=True, format="ms"):
- # Get child xforms from the prototype path
- child_xforms = []
- if isinstance(source, str):
- # If source is a file path, load the stage
- stage = Usd.Stage.Open(source)
- else:
- # If source is already a stage
- stage = source
-
- # Get the prototype prim
- prototype_prim = stage.GetPrimAtPath(prototype_path)
- if prototype_prim.IsValid():
- # Get all child prims that are Xforms
- for child_prim in prototype_prim.GetAllChildren():
- if child_prim.GetTypeName() == "Xform":
- child_xforms.append(child_prim.GetPath().pathString)
-
- # If no child xforms found, use the prototype path itself
- if not child_xforms:
- child_xforms = [prototype_path]
-
- prototype_builder = ModelBuilder(up_axis=up_axis)
- for child_path in child_xforms:
- prototype_builder.add_usd(
- source,
- root_path=child_path,
- load_non_physics_prims=False,
- **usd_kwargs,
- )
- prototype_builder.approximate_meshes("convex_hull")
-
- with Timer(name="newton_multiple_add_to_builder", msg="All add to builder took:", enable=True, format="ms"):
- # clone the prototype env with updated paths
- for i, (pos, ori) in enumerate(zip(positions, orientations)):
- body_start = builder.body_count
- shape_start = builder.shape_count
- joint_start = builder.joint_count
- articulation_start = builder.articulation_count
-
- builder.add_builder(
- prototype_builder, xform=wp.transform(np.array(pos) + np.array(spawn_offset), wp.quat_identity())
- )
-
- if i > 0:
- update_paths(
- builder,
- prototype_path,
- path_pattern.format(i),
- body_start=body_start,
- shape_start=shape_start,
- joint_start=joint_start,
- articulation_start=articulation_start,
- )
-
- return builder, stage_info
-
-
-def update_paths(
- builder: ModelBuilder,
- old_root: str,
- new_root: str,
- body_start: int | None = None,
- shape_start: int | None = None,
- joint_start: int | None = None,
- articulation_start: int | None = None,
-) -> None:
- """Updates the paths of the builder to match the new root path.
-
- Args:
- builder (ModelBuilder): The builder to update.
- old_root (str): The old root path.
- new_root (str): The new root path.
- body_start (int): The start index of the bodies.
- shape_start (int): The start index of the shapes.
- joint_start (int): The start index of the joints.
- articulation_start (int): The start index of the articulations.
- """
- old_len = len(old_root)
- if body_start is not None:
- for i in range(body_start, builder.body_count):
- builder.body_key[i] = f"{new_root}{builder.body_key[i][old_len:]}"
- if shape_start is not None:
- for i in range(shape_start, builder.shape_count):
- builder.shape_key[i] = f"{new_root}{builder.shape_key[i][old_len:]}"
- if joint_start is not None:
- for i in range(joint_start, builder.joint_count):
- builder.joint_key[i] = f"{new_root}{builder.joint_key[i][old_len:]}"
- if articulation_start is not None:
- for i in range(articulation_start, builder.articulation_count):
- builder.articulation_key[i] = f"{new_root}{builder.articulation_key[i][old_len:]}"
diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py
index 20c1c39a366..0a6bbb51e41 100644
--- a/source/isaaclab/isaaclab/envs/direct_rl_env.py
+++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py
@@ -5,7 +5,7 @@
from __future__ import annotations
-import builtins
+import contextlib
import gymnasium as gym
import inspect
import logging
@@ -18,15 +18,10 @@
from dataclasses import MISSING
from typing import Any, ClassVar
-import omni.kit.app
-import omni.physx
-from isaacsim.core.simulation_manager import SimulationManager
-from isaacsim.core.version import get_version
-
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 import use_stage
from isaaclab.utils.noise import NoiseModel
from isaaclab.utils.seed import configure_seed
from isaaclab.utils.timer import Timer
@@ -36,6 +31,11 @@
from .ui import ViewportCameraController
from .utils.spaces import sample_space, spec_to_gym_space
+# import omni.physx
+# from isaacsim.core.simulation_manager import SimulationManager
+# from isaacsim.core.version import get_version
+
+
# import logger
logger = logging.getLogger(__name__)
@@ -69,7 +69,7 @@ class DirectRLEnv(gym.Env):
"""Whether the environment is a vectorized environment."""
metadata: ClassVar[dict[str, Any]] = {
"render_modes": [None, "human", "rgb_array"],
- "isaac_sim_version": get_version(),
+ # "isaac_sim_version": get_version(),
}
"""Metadata for the environment."""
@@ -132,7 +132,7 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs
with use_stage(self.sim.get_initial_stage()):
self.scene = InteractiveScene(self.cfg.scene)
self._setup_scene()
- attach_stage_to_usd_context()
+ # attach_stage_to_usd_context()
print("[INFO]: Scene manager: ", self.scene)
# set up camera viewport controller
@@ -157,17 +157,17 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs
# play the simulator to activate physics handles
# note: this activates the physics simulation view that exposes TensorAPIs
# note: when started in extension mode, first call sim.reset_async() and then initialize the managers
- if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False:
- print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...")
- with Timer("[INFO]: Time taken for simulation start", "simulation_start"):
- # since the reset can trigger callbacks which use the stage,
- # we need to set the stage context here
- with use_stage(self.sim.get_initial_stage()):
- self.sim.reset()
- # update scene to pre populate data buffers for assets and sensors.
- # this is needed for the observation manager to get valid tensors for initialization.
- # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset.
- self.scene.update(dt=self.physics_dt)
+ # if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False:
+ print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...")
+ with Timer("[INFO]: Time taken for simulation start", "simulation_start"):
+ # since the reset can trigger callbacks which use the stage,
+ # we need to set the stage context here
+ with use_stage(self.sim.get_initial_stage()):
+ self.sim.reset()
+ # update scene to pre populate data buffers for assets and sensors.
+ # this is needed for the observation manager to get valid tensors for initialization.
+ # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset.
+ self.scene.update(dt=self.physics_dt)
# check if debug visualization is has been implemented by the environment
source_code = inspect.getsource(self._set_debug_vis_impl)
@@ -227,7 +227,9 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs
def __del__(self):
"""Cleanup for the environment."""
- self.close()
+ # Suppress errors during Python shutdown to avoid noisy tracebacks
+ with contextlib.suppress(ImportError, AttributeError, TypeError):
+ self.close()
"""
Properties.
@@ -305,9 +307,10 @@ def reset(self, seed: int | None = None, options: dict[str, Any] | None = None)
if self.sim.has_rtx_sensors() and self.cfg.rerender_on_reset:
self.sim.render()
- if self.cfg.wait_for_textures and self.sim.has_rtx_sensors():
- while SimulationManager.assets_loading():
- self.sim.render()
+ # TODO: Fix this
+ # if self.cfg.wait_for_textures and self.sim.has_rtx_sensors():
+ # while SimulationManager.assets_loading():
+ # self.sim.render()
# return observations
return self._get_observations(), self.extras
@@ -497,15 +500,15 @@ def close(self):
if self.viewport_camera_controller is not None:
del self.viewport_camera_controller
- # clear callbacks and instance
- if float(".".join(get_version()[2])) >= 5:
- if self.cfg.sim.create_stage_in_memory:
- # detach physx stage
- omni.physx.get_physx_simulation_interface().detach_stage()
- self.sim.stop()
- self.sim.clear()
+ # # clear callbacks and instance
+ # if float(".".join(get_version()[2])) >= 5:
+ # if self.cfg.sim.create_stage_in_memory:
+ # # detach physx stage
+ # omni.physx.get_physx_simulation_interface().detach_stage()
+ # self.sim.stop()
+ # self.sim.clear()
- self.sim.clear_all_callbacks()
+ # self.sim.clear_all_callbacks()
self.sim.clear_instance()
# destroy the window
@@ -528,6 +531,8 @@ def set_debug_vis(self, debug_vis: bool) -> bool:
Whether the debug visualization was successfully set. False if the environment
does not support debug visualization.
"""
+ import omni.kit.app
+
# check if debug visualization is supported
if not self.has_debug_vis_implementation:
return False
diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py
index 14cf0332030..a55496e6eb4 100644
--- a/source/isaaclab/isaaclab/envs/manager_based_env.py
+++ b/source/isaaclab/isaaclab/envs/manager_based_env.py
@@ -4,19 +4,16 @@
# SPDX-License-Identifier: BSD-3-Clause
import builtins
+import contextlib
import logging
import torch
from collections.abc import Sequence
from typing import Any
-import omni.physx
-from isaacsim.core.simulation_manager import SimulationManager
-from isaacsim.core.version import get_version
-
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 import use_stage
from isaaclab.ui.widgets import ManagerLiveVisualizer
from isaaclab.utils.seed import configure_seed
from isaaclab.utils.timer import Timer
@@ -25,6 +22,11 @@
from .manager_based_env_cfg import ManagerBasedEnvCfg
from .ui import ViewportCameraController
+# import omni.physx
+# from isaacsim.core.simulation_manager import SimulationManager
+# from isaacsim.core.version import get_version
+
+
# import logger
logger = logging.getLogger(__name__)
@@ -136,7 +138,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg):
# set the stage context for scene creation steps which use the stage
with use_stage(self.sim.get_initial_stage()):
self.scene = InteractiveScene(self.cfg.scene)
- attach_stage_to_usd_context()
+ # attach_stage_to_usd_context()
print("[INFO]: Scene manager: ", self.scene)
# set up camera viewport controller
@@ -160,19 +162,19 @@ def __init__(self, cfg: ManagerBasedEnvCfg):
# play the simulator to activate physics handles
# note: this activates the physics simulation view that exposes TensorAPIs
# note: when started in extension mode, first call sim.reset_async() and then initialize the managers
- if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False:
- print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...")
- with Timer("[INFO]: Time taken for simulation start", "simulation_start"):
- # since the reset can trigger callbacks which use the stage,
- # we need to set the stage context here
- with use_stage(self.sim.get_initial_stage()):
- self.sim.reset()
- # update scene to pre populate data buffers for assets and sensors.
- # this is needed for the observation manager to get valid tensors for initialization.
- # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset.
- self.scene.update(dt=self.physics_dt)
- # add timeline event to load managers
- self.load_managers()
+ # if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False:
+ print("[INFO]: Starting the simulation. This may take a few seconds. Please wait...")
+ with Timer("[INFO]: Time taken for simulation start", "simulation_start"):
+ # since the reset can trigger callbacks which use the stage,
+ # we need to set the stage context here
+ with use_stage(self.sim.get_initial_stage()):
+ self.sim.reset()
+ # update scene to pre populate data buffers for assets and sensors.
+ # this is needed for the observation manager to get valid tensors for initialization.
+ # this shouldn't cause an issue since later on, users do a reset over all the environments so the lazy buffers would be reset.
+ self.scene.update(dt=self.physics_dt)
+ # add timeline event to load managers
+ self.load_managers()
# extend UI elements
# we need to do this here after all the managers are initialized
@@ -190,7 +192,9 @@ def __init__(self, cfg: ManagerBasedEnvCfg):
def __del__(self):
"""Cleanup for the environment."""
- self.close()
+ # Suppress errors during Python shutdown to avoid noisy tracebacks
+ with contextlib.suppress(ImportError, AttributeError, TypeError):
+ self.close()
"""
Properties.
@@ -318,9 +322,10 @@ def reset(
# compute observations
self.obs_buf = self.observation_manager.compute(update_history=True)
- if self.cfg.wait_for_textures and self.sim.has_rtx_sensors():
- while SimulationManager.assets_loading():
- self.sim.render()
+ # TODO: Fix this
+ # if self.cfg.wait_for_textures and self.sim.has_rtx_sensors():
+ # while SimulationManager.assets_loading():
+ # self.sim.render()
# return observations
return self.obs_buf, self.extras
@@ -463,15 +468,15 @@ def close(self):
del self.recorder_manager
del self.scene
- # clear callbacks and instance
- if float(".".join(get_version()[2])) >= 5:
- if self.cfg.sim.create_stage_in_memory:
- # detach physx stage
- omni.physx.get_physx_simulation_interface().detach_stage()
- self.sim.stop()
- self.sim.clear()
+ # # clear callbacks and instance
+ # if float(".".join(get_version()[2])) >= 5:
+ # if self.cfg.sim.create_stage_in_memory:
+ # # detach physx stage
+ # omni.physx.get_physx_simulation_interface().detach_stage()
+ # self.sim.stop()
+ # self.sim.clear()
- self.sim.clear_all_callbacks()
+ # self.sim.clear_all_callbacks()
self.sim.clear_instance()
# destroy the window
diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py
index 6f93d7a945f..de4b8c773a3 100644
--- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py
+++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py
@@ -13,8 +13,6 @@
from collections.abc import Sequence
from typing import Any, ClassVar
-from isaacsim.core.version import get_version
-
from isaaclab.managers import CommandManager, CurriculumManager, RewardManager, TerminationManager
from isaaclab.ui.widgets import ManagerLiveVisualizer
from isaaclab.utils.timer import Timer
@@ -58,7 +56,7 @@ class ManagerBasedRLEnv(ManagerBasedEnv, gym.Env):
"""Whether the environment is a vectorized environment."""
metadata: ClassVar[dict[str, Any]] = {
"render_modes": [None, "human", "rgb_array"],
- "isaac_sim_version": get_version(),
+ # "isaac_sim_version": get_version(),
}
"""Metadata for the environment."""
diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py
index 1ef548b3acb..1a5b0b46b38 100644
--- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py
+++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py
@@ -11,10 +11,6 @@
from datetime import datetime
from typing import TYPE_CHECKING
-import isaacsim
-import omni.kit.app
-import omni.kit.commands
-import omni.usd
from pxr import Sdf, Usd, UsdGeom, UsdPhysics
from isaaclab.sim.utils.stage import get_current_stage
@@ -50,6 +46,8 @@ def __init__(self, env: ManagerBasedEnv, window_name: str = "IsaacLab"):
env: The environment object.
window_name: The name of the window. Defaults to "IsaacLab".
"""
+ import omni.ui
+
# store inputs
self.env = env
# prepare the list of assets that can be followed by the viewport camera
@@ -134,6 +132,9 @@ def _check_live_plots_enabled(self) -> bool:
def _build_sim_frame(self):
"""Builds the sim-related controls frame for the UI."""
+ import isaacsim
+ import omni.ui
+
# create collapsable frame for controls
self.ui_window_elements["sim_frame"] = omni.ui.CollapsableFrame(
title="Simulation Settings",
@@ -178,6 +179,9 @@ def _build_sim_frame(self):
def _build_viewer_frame(self):
"""Build the viewer-related control frame for the UI."""
+ import isaacsim
+ import omni.ui
+
# create collapsable frame for viewer
self.ui_window_elements["viewer_frame"] = omni.ui.CollapsableFrame(
title="Viewer Settings",
@@ -245,6 +249,9 @@ def _build_debug_vis_frame(self):
that has it implemented. If the element does not have a debug visualization implemented,
a label is created instead.
"""
+ import isaacsim
+ import omni.ui
+
# create collapsable frame for debug visualization
self.ui_window_elements["debug_frame"] = omni.ui.CollapsableFrame(
title="Scene Debug Visualization",
@@ -300,6 +307,9 @@ def _visualize_manager(self, title: str, class_name: str) -> None:
def _toggle_recording_animation_fn(self, value: bool):
"""Toggles the animation recording."""
+ import omni.kit.commands
+ import omni.usd
+
if value:
# log directory to save the recording
if not hasattr(self, "animation_log_dir"):
@@ -426,6 +436,8 @@ def _set_viewer_env_index_fn(self, model: omni.ui.SimpleIntModel):
def _create_debug_vis_ui_element(self, name: str, elem: object):
"""Create a checkbox for toggling debug visualization for the given element."""
+ import isaacsim
+ import omni.ui
from omni.kit.window.extensions import SimpleCheckBox
with omni.ui.HStack():
@@ -475,6 +487,8 @@ def _create_debug_vis_ui_element(self, name: str, elem: object):
async def _dock_window(self, window_title: str):
"""Docks the custom UI window to the property window."""
+ import omni.ui
+
# wait for the window to be created
for _ in range(5):
if omni.ui.Workspace.get_window(window_title):
diff --git a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py
index 15fc6817418..bab814f906f 100644
--- a/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py
+++ b/source/isaaclab/isaaclab/envs/ui/viewport_camera_controller.py
@@ -12,9 +12,6 @@
from collections.abc import Sequence
from typing import TYPE_CHECKING
-import omni.kit.app
-import omni.timeline
-
from isaaclab.assets.articulation.articulation import Articulation
if TYPE_CHECKING:
@@ -74,6 +71,8 @@ def __init__(self, env: ManagerBasedEnv | DirectRLEnv, cfg: ViewerCfg):
# set the camera origin to the center of the world
self.update_view_to_world()
+ import omni.kit.app
+
# subscribe to post update event so that camera view can be updated at each rendering step
app_interface = omni.kit.app.get_app_interface()
app_event_stream = app_interface.get_post_update_event_stream()
diff --git a/source/isaaclab/isaaclab/managers/manager_base.py b/source/isaaclab/isaaclab/managers/manager_base.py
index 11ed7e3defc..3ce41c0536d 100644
--- a/source/isaaclab/isaaclab/managers/manager_base.py
+++ b/source/isaaclab/isaaclab/managers/manager_base.py
@@ -5,22 +5,23 @@
from __future__ import annotations
+import contextlib
import copy
import inspect
import logging
-import weakref
from abc import ABC, abstractmethod
from collections.abc import Sequence
from typing import TYPE_CHECKING, Any
-import omni.timeline
-
import isaaclab.utils.string as string_utils
from isaaclab.utils import class_to_dict, string_to_callable
from .manager_term_cfg import ManagerTermBaseCfg
from .scene_entity_cfg import SceneEntityCfg
+# import omni.timeline
+
+
if TYPE_CHECKING:
from isaaclab.envs import ManagerBasedEnv
@@ -157,19 +158,20 @@ def __init__(self, cfg: object, env: ManagerBasedEnv):
# simulation, but before the simulation is playing.
# FIXME: Once Isaac Sim supports storing this information as USD schema, we can remove this
# callback and resolve the scene entities directly inside `_prepare_terms`.
- if not self._env.sim.is_playing():
- # note: Use weakref on all callbacks to ensure that this object can be deleted when its destructor
- # is called
- # The order is set to 20 to allow asset/sensor initialization to complete before the scene entities
- # are resolved. Those have the order 10.
- timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
- self._resolve_terms_handle = timeline_event_stream.create_subscription_to_pop_by_type(
- int(omni.timeline.TimelineEventType.PLAY),
- lambda event, obj=weakref.proxy(self): obj._resolve_terms_callback(event),
- order=20,
- )
- else:
- self._resolve_terms_handle = None
+ # if not self._env.sim.is_playing():
+ # # note: Use weakref on all callbacks to ensure that this object can be deleted when its destructor
+ # # is called
+ # # The order is set to 20 to allow asset/sensor initialization to complete before the scene entities
+ # # are resolved. Those have the order 10.
+ # timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
+ # self._resolve_terms_handle = timeline_event_stream.create_subscription_to_pop_by_type(
+ # int(omni.timeline.TimelineEventType.PLAY),
+ # lambda event, obj=weakref.proxy(self): obj._resolve_terms_callback(event),
+ # order=20,
+ # )
+ # else:
+ # self._resolve_terms_handle = None
+ self._resolve_terms_handle = None
# parse config to create terms information
if self.cfg:
@@ -177,9 +179,11 @@ def __init__(self, cfg: object, env: ManagerBasedEnv):
def __del__(self):
"""Delete the manager."""
- if self._resolve_terms_handle:
- self._resolve_terms_handle.unsubscribe()
- self._resolve_terms_handle = None
+ # Suppress errors during Python shutdown
+ with contextlib.suppress(ImportError, AttributeError, TypeError):
+ if getattr(self, "_resolve_terms_handle", None):
+ self._resolve_terms_handle.unsubscribe()
+ self._resolve_terms_handle = None
"""
Properties.
diff --git a/source/isaaclab/isaaclab/markers/visualization_markers.py b/source/isaaclab/isaaclab/markers/visualization_markers.py
index f6193119063..8208df088b3 100644
--- a/source/isaaclab/isaaclab/markers/visualization_markers.py
+++ b/source/isaaclab/isaaclab/markers/visualization_markers.py
@@ -24,14 +24,11 @@
import torch
from dataclasses import MISSING
-import omni.kit.commands
-import omni.physx.scripts.utils as physx_utils
from pxr import Gf, 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.sim.utils.stage import get_current_stage
from isaaclab.utils.configclass import configclass
from isaaclab.utils.math import convert_quat
@@ -401,20 +398,15 @@ def _process_prototype_prim(self, prim: Usd.Prim):
child_prim.SetInstanceable(False)
# check if prim is a mesh -> if so, make it invisible to secondary rays
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)
-
- # invisible to secondary rays such as depth images
- omni.kit.commands.execute(
- "ChangePropertyCommand",
- prop_path=Sdf.Path(f"{child_prim.GetPrimPath().pathString}.primvars:invisibleToSecondaryRays"),
- value=True,
- prev=None,
- type_to_create_if_not_exist=Sdf.ValueTypeNames.Bool,
- )
+ # invisible to secondary rays such as depth images using USD core API
+ attr = child_prim.GetAttribute("primvars:invisibleToSecondaryRays")
+ if not attr:
+ attr = child_prim.CreateAttribute("primvars:invisibleToSecondaryRays", Sdf.ValueTypeNames.Bool)
+ attr.Set(True)
# add children to list
all_prims += child_prim.GetChildren()
# remove any physics on the markers because they are only for visualization!
+ import omni.physx.scripts.utils as physx_utils
+
physx_utils.removeRigidBodySubtree(prim)
diff --git a/source/isaaclab/isaaclab/scene/cloner.py b/source/isaaclab/isaaclab/scene/cloner.py
new file mode 100644
index 00000000000..277df58a3f3
--- /dev/null
+++ b/source/isaaclab/isaaclab/scene/cloner.py
@@ -0,0 +1,240 @@
+# 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 math
+import torch
+
+import warp as wp
+from newton import AxisType, ModelBuilder
+from pxr import Sdf, Usd, UsdGeom, UsdUtils
+
+CLONE = {
+ "source": [],
+ "destination": [],
+ "mapping": torch.empty((0,), dtype=torch.bool),
+}
+
+
+def usd_replicate(stage: Usd.Stage, sources: list[str], destinations: list[str], mapping: torch.Tensor) -> None:
+ root_layer = stage.GetRootLayer()
+ with Sdf.ChangeBlock():
+ for i, src in enumerate(sources):
+ template = destinations[i]
+ env_ids = torch.nonzero(mapping[i], as_tuple=True)[0].tolist()
+ for w in env_ids:
+ dest_path = template.format(int(w))
+ # create the prim at destination then copy spec from src -> dest
+ Sdf.CreatePrimInLayer(root_layer, dest_path)
+ Sdf.CopySpec(root_layer, Sdf.Path(src), root_layer, Sdf.Path(dest_path))
+
+
+def physx_replicate(
+ stage: Usd.Stage,
+ mapping: dict[str, list[str]],
+ num_envs: int,
+ *,
+ use_env_ids: bool = True,
+ use_fabric: bool = False,
+) -> None:
+ from omni.physx import get_physx_replicator_interface
+
+ stage_id = UsdUtils.StageCache.Get().Insert(stage).ToLongInt()
+ current_dests: list[str] = [] # mutated per batch so rename_fn indexes the right list
+
+ def attach_fn(_stage_id: int):
+ return ["/World/envs", *list(mapping.keys())]
+
+ def rename_fn(_replicate_path: str, i: int):
+ return current_dests[i]
+
+ def attach_end_fn(_stage_id: int):
+ rep = get_physx_replicator_interface()
+ for src, dests in mapping.items():
+ if len(dests) > 0:
+ current_dests[:] = dests
+ rep.replicate(
+ _stage_id, src, len(dests), useEnvIds=len(dests) == num_envs, useFabricForReplication=use_fabric
+ )
+ if src not in dests:
+ stage.GetPrimAtPath(src).SetActive(False)
+ # unregister only AFTER all replicate() calls completed
+ rep.unregister_replicator(_stage_id)
+
+ get_physx_replicator_interface().register_replicator(stage_id, attach_fn, attach_end_fn, rename_fn)
+
+
+def newton_replicate(
+ stage: Usd.Stage,
+ sources: list[str],
+ destinations: list[str],
+ mapping: torch.Tensor,
+ positions,
+ orientations,
+ up_axis: AxisType = "Z",
+ simplify_meshes: bool = True,
+):
+
+ from isaaclab.sim._impl.newton_manager import NewtonManager
+
+ # load everything except the prototype subtrees
+ builder = ModelBuilder(up_axis=up_axis)
+ stage_info = builder.add_usd(stage, ignore_paths=sources, load_non_physics_prims=False)
+
+ # build a prototype for each source
+ protos: dict[str, ModelBuilder] = {}
+ for src_path in sources:
+ p = ModelBuilder(up_axis=up_axis)
+ p.add_usd(stage, root_path=src_path, load_non_physics_prims=False)
+ if simplify_meshes:
+ p.approximate_meshes("convex_hull")
+ protos[src_path] = p
+
+ # add by world, then by active sources in that world (column-wise)
+ for w in range(mapping.size(1)):
+ for j in torch.nonzero(mapping[:, w], as_tuple=True)[0]:
+ builder.add_builder(protos[sources[j]], xform=wp.transform(positions[w], orientations[w]), world=w)
+
+ # per-source, per-world renaming (strict prefix swap), compact style preserved
+ for i, src_path in enumerate(sources):
+ ol = len(src_path.rstrip("/"))
+ swap = lambda name, new_root: new_root + name[ol:] # noqa: E731
+ worlds_list = torch.nonzero(mapping[i], as_tuple=True)[0].tolist()
+ world_roots = {w: destinations[i].format(w) for w in worlds_list}
+
+ for t in ("body", "joint", "shape", "articulation"):
+ keys, worlds_arr = getattr(builder, f"{t}_key"), getattr(builder, f"{t}_world")
+ for k, w in enumerate(worlds_arr):
+ if w in world_roots and keys[k].startswith(src_path):
+ keys[k] = swap(keys[k], world_roots[w])
+
+ NewtonManager.set_builder(builder)
+ NewtonManager._num_envs = mapping.size(1)
+ return builder, stage_info
+
+
+def filter_collisions(
+ stage: Usd.Stage,
+ physicsscene_path: str,
+ collision_root_path: str,
+ prim_paths: list[str],
+ global_paths: list[str] = [],
+):
+ """Filters collisions between clones. Clones will not collide with each other, but can collide with objects specified in global_paths.
+
+ Args:
+ physicsscene_path (str): Path to PhysicsScene object in stage.
+ collision_root_path (str): Path to place collision groups under.
+ prim_paths (List[str]): Paths of objects to filter out collision.
+ global_paths (List[str]): Paths of objects to generate collision (e.g. ground plane).
+
+ """
+ from pxr import PhysxSchema
+
+ physx_scene = PhysxSchema.PhysxSceneAPI(stage.GetPrimAtPath(physicsscene_path))
+
+ # We invert the collision group filters for more efficient collision filtering across environments
+ physx_scene.CreateInvertCollisionGroupFilterAttr().Set(True)
+
+ # Make sure we create the collision_scope in the RootLayer since the edit target may be a live layer in the case of Live Sync.
+ with Usd.EditContext(stage, Usd.EditTarget(stage.GetRootLayer())):
+ UsdGeom.Scope.Define(stage, collision_root_path)
+
+ with Sdf.ChangeBlock():
+ if len(global_paths) > 0:
+ global_collision_group_path = collision_root_path + "/global_group"
+ # add collision group prim
+ global_collision_group = Sdf.PrimSpec(
+ stage.GetRootLayer().GetPrimAtPath(collision_root_path),
+ "global_group",
+ Sdf.SpecifierDef,
+ "PhysicsCollisionGroup",
+ )
+ # prepend collision API schema
+ global_collision_group.SetInfo(Usd.Tokens.apiSchemas, Sdf.TokenListOp.Create({"CollectionAPI:colliders"}))
+
+ # expansion rule
+ expansion_rule = Sdf.AttributeSpec(
+ global_collision_group,
+ "collection:colliders:expansionRule",
+ Sdf.ValueTypeNames.Token,
+ Sdf.VariabilityUniform,
+ )
+ expansion_rule.default = "expandPrims"
+
+ # includes rel
+ global_includes_rel = Sdf.RelationshipSpec(global_collision_group, "collection:colliders:includes", False)
+ for global_path in global_paths:
+ global_includes_rel.targetPathList.Append(global_path)
+
+ # filteredGroups rel
+ global_filtered_groups = Sdf.RelationshipSpec(global_collision_group, "physics:filteredGroups", False)
+ # We are using inverted collision group filtering, which means objects by default don't collide across
+ # groups. We need to add this group as a filtered group, so that objects within this group collide with
+ # each other.
+ global_filtered_groups.targetPathList.Append(global_collision_group_path)
+
+ # set collision groups and filters
+ for i, prim_path in enumerate(prim_paths):
+ collision_group_path = collision_root_path + f"/group{i}"
+ # add collision group prim
+ collision_group = Sdf.PrimSpec(
+ stage.GetRootLayer().GetPrimAtPath(collision_root_path),
+ f"group{i}",
+ Sdf.SpecifierDef,
+ "PhysicsCollisionGroup",
+ )
+ # prepend collision API schema
+ collision_group.SetInfo(Usd.Tokens.apiSchemas, Sdf.TokenListOp.Create({"CollectionAPI:colliders"}))
+
+ # expansion rule
+ expansion_rule = Sdf.AttributeSpec(
+ collision_group,
+ "collection:colliders:expansionRule",
+ Sdf.ValueTypeNames.Token,
+ Sdf.VariabilityUniform,
+ )
+ expansion_rule.default = "expandPrims"
+
+ # includes rel
+ includes_rel = Sdf.RelationshipSpec(collision_group, "collection:colliders:includes", False)
+ includes_rel.targetPathList.Append(prim_path)
+
+ # filteredGroups rel
+ filtered_groups = Sdf.RelationshipSpec(collision_group, "physics:filteredGroups", False)
+ # We are using inverted collision group filtering, which means objects by default don't collide across
+ # groups. We need to add this group as a filtered group, so that objects within this group collide with
+ # each other.
+ filtered_groups.targetPathList.Append(collision_group_path)
+ if len(global_paths) > 0:
+ filtered_groups.targetPathList.Append(global_collision_group_path)
+ global_filtered_groups.targetPathList.Append(collision_group_path)
+
+
+def grid_transforms(N: int, spacing: float = 1.0, up_axis: str = "z", device="cpu"):
+ # rows/cols
+ rows = int(math.ceil(math.sqrt(N)))
+ cols = int(math.ceil(N / rows))
+
+ idx = torch.arange(N, device=device)
+ r = torch.div(idx, cols, rounding_mode="floor")
+ c = idx % cols
+
+ # centered grid coords
+ x = (c - (cols - 1) * 0.5) * spacing
+ y = ((rows - 1) * 0.5 - r) * spacing
+
+ # place on plane based on up_axis
+ z0 = torch.zeros_like(x)
+ if up_axis.lower() == "z":
+ pos = torch.stack([x, y, z0], dim=1)
+ elif up_axis.lower() == "y":
+ pos = torch.stack([x, z0, y], dim=1)
+ else: # up_axis == "x"
+ pos = torch.stack([z0, x, y], dim=1)
+
+ # identity orientations (w,x,y,z)
+ ori = torch.zeros((N, 4), device=device)
+ ori[:, 0] = 1.0
+ return pos, ori
diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py
index 762535332dc..84df8ca9e96 100644
--- a/source/isaaclab/isaaclab/scene/interactive_scene.py
+++ b/source/isaaclab/isaaclab/scene/interactive_scene.py
@@ -3,22 +3,19 @@
#
# SPDX-License-Identifier: BSD-3-Clause
+from __future__ import annotations
+
import logging
import torch
from collections.abc import Sequence
from typing import Any
-import carb
-from isaacsim.core.prims import XFormPrim
-from isaacsim.core.version import get_version
-
import isaaclab.sim as sim_utils
+from isaaclab import cloner
from isaaclab.assets import Articulation, ArticulationCfg, AssetBaseCfg
-from isaaclab.cloner import GridCloner
from isaaclab.sensors import ContactSensorCfg, 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
+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
@@ -122,58 +119,36 @@ def __init__(self, cfg: InteractiveSceneCfg):
# physics scene path
self._physics_scene_path = None
# prepare cloner for environment replication
- self.cloner = GridCloner(spacing=self.cfg.env_spacing, stage=self.stage)
- self.cloner.define_base_env(self.env_ns)
- self.env_prim_paths = self.cloner.generate_paths(f"{self.env_ns}/env", self.cfg.num_envs)
+ self.env_prim_paths = [f"{self.env_ns}/env_{i}" for i in range(self.cfg.num_envs)]
+
+ self.cloner_cfg = cloner.TemplateCloneCfg(
+ clone_regex=self.env_regex_ns,
+ clone_in_fabric=self.cfg.clone_in_fabric,
+ device=self.device,
+ )
+
# create source prim
self.stage.DefinePrim(self.env_prim_paths[0], "Xform")
-
- # when replicate_physics=False, we assume heterogeneous environments and clone the xforms first.
- # this triggers per-object level cloning in the spawner.
- if not self.cfg.replicate_physics:
- # check version of Isaac Sim to determine whether clone_in_fabric is valid
- isaac_sim_version = float(".".join(get_version()[2]))
- if isaac_sim_version < 5:
- # clone the env xform
- env_origins = self.cloner.clone(
- source_prim_path=self.env_prim_paths[0],
- prim_paths=self.env_prim_paths,
- replicate_physics=False,
- copy_from_source=True,
- enable_env_ids=(
- self.cfg.filter_collisions if self.device != "cpu" else False
- ), # this won't do anything because we are not replicating physics
- )
- else:
- # clone the env xform
- env_origins = self.cloner.clone(
- source_prim_path=self.env_prim_paths[0],
- prim_paths=self.env_prim_paths,
- replicate_physics=False,
- copy_from_source=True,
- enable_env_ids=(
- self.cfg.filter_collisions if self.device != "cpu" else False
- ), # this won't do anything because we are not replicating physics
- clone_in_fabric=self.cfg.clone_in_fabric,
- )
- self._default_env_origins = torch.tensor(env_origins, device=self.device, dtype=torch.float32)
- else:
- # otherwise, environment origins will be initialized during cloning at the end of environment creation
- self._default_env_origins = None
+ self.stage.DefinePrim(self.cloner_cfg.template_root, "Xform")
+ self.env_fmt = self.env_regex_ns.replace(".*", "{}")
+ # allocate env indices
+ self._ALL_INDICES = torch.arange(self.cfg.num_envs, dtype=torch.long, device=self.device)
+ self._default_env_origins, _ = cloner.grid_transforms(self.num_envs, self.cfg.env_spacing, device=self.device)
+ # copy empty prim of env_0 to env_1, env_2, ..., env_{num_envs-1} with correct location.
+ cloner.usd_replicate(
+ self.stage, [self.env_fmt.format(0)], [self.env_fmt], self._ALL_INDICES, positions=self._default_env_origins
+ )
self._global_prim_paths = list()
if self._is_scene_setup_from_cfg():
- # add entities from config
+ self._global_template_prim_paths = list() # store paths that are in global collision filter from templates
self._add_entities_from_cfg()
- # clone environments on a global scope if environment is homogeneous
- if self.cfg.replicate_physics:
- self.clone_environments(copy_from_source=False)
- # replicate physics if we have more than one environment
- # this is done to make scene initialization faster at play time
- # since env_ids is only applicable when replicating physics, we have to fallback to the previous method
- # to filter collisions if replicate_physics is not enabled
- # additionally, env_ids is only supported in GPU simulation
- if (not self.cfg.replicate_physics and self.cfg.filter_collisions) or self.device == "cpu":
+ for prim_path in self._global_template_prim_paths:
+ filter_regex = prim_path.replace(self.cloner_cfg.template_root, self.env_regex_ns)
+ self._global_prim_paths.extend(sim_utils.find_matching_prim_paths(filter_regex))
+
+ self.clone_environments(copy_from_source=(not self.cfg.replicate_physics))
+ if self.cfg.filter_collisions:
self.filter_collisions(self._global_prim_paths)
def clone_environments(self, copy_from_source: bool = False):
@@ -184,58 +159,23 @@ def clone_environments(self, copy_from_source: bool = False):
If True, clones are independent copies of the source prim and won't reflect its changes (start-up time
may increase). Defaults to False.
"""
- # check if user spawned different assets in individual environments
- # this flag will be None if no multi asset is spawned
- carb_settings_iface = carb.settings.get_settings()
- has_multi_assets = carb_settings_iface.get("/isaaclab/spawn/multi_assets")
- if has_multi_assets and self.cfg.replicate_physics:
- logger.warning(
- "Varying assets might have been spawned under different environments."
- " However, the replicate physics flag is enabled in the 'InteractiveScene' configuration."
- " This may adversely affect PhysX parsing. We recommend disabling this property."
- )
-
- # check version of Isaac Sim to determine whether clone_in_fabric is valid
- isaac_sim_version = float(".".join(get_version()[2]))
- if isaac_sim_version < 5:
- # clone the environment
- env_origins = self.cloner.clone(
- source_prim_path=self.env_prim_paths[0],
- prim_paths=self.env_prim_paths,
- replicate_physics=self.cfg.replicate_physics,
- copy_from_source=copy_from_source,
- enable_env_ids=(
- self.cfg.filter_collisions if self.device != "cpu" else False
- ), # this automatically filters collisions between environments
- )
+ # when replicate_physics=False, we assume heterogeneous environments and clone the xforms first.
+ # this triggers per-object level cloning in the spawner.
+ # if self.cfg.replicate_physics:
+ # prim = self.stage.GetPrimAtPath("/physicsScene")
+ # prim.CreateAttribute("physxScene:envIdInBoundsBitCount", Sdf.ValueTypeNames.Int).Set(4)
+
+ if self._is_scene_setup_from_cfg():
+ self.cloner_cfg.clone_physics = not copy_from_source
+ cloner.clone_from_template(self.stage, num_clones=self.num_envs, template_clone_cfg=self.cloner_cfg)
else:
- # clone the environment
- env_origins = self.cloner.clone(
- source_prim_path=self.env_prim_paths[0],
- prim_paths=self.env_prim_paths,
- replicate_physics=self.cfg.replicate_physics,
- copy_from_source=copy_from_source,
- enable_env_ids=(
- self.cfg.filter_collisions if self.device != "cpu" else False
- ), # this automatically filters collisions between environments
- clone_in_fabric=self.cfg.clone_in_fabric,
- )
-
- # since env_ids is only applicable when replicating physics, we have to fallback to the previous method
- # to filter collisions if replicate_physics is not enabled
- # additionally, env_ids is only supported in GPU simulation
- if (not self.cfg.replicate_physics and self.cfg.filter_collisions) or self.device == "cpu":
- # if scene is specified through cfg, this is already taken care of
- if not self._is_scene_setup_from_cfg():
- logger.warning(
- "Collision filtering can only be automatically enabled when replicate_physics=True and using GPU"
- " simulation. Please call scene.filter_collisions(global_prim_paths) to filter collisions across"
- " environments."
- )
-
- # in case of heterogeneous cloning, the env origins is specified at init
- if self._default_env_origins is None:
- self._default_env_origins = torch.tensor(env_origins, device=self.device, dtype=torch.float32)
+ mapping = torch.ones((1, self.num_envs), device=self.device, dtype=torch.bool)
+ replicate_args = [self.env_fmt.format(0)], [self.env_fmt], self._ALL_INDICES, mapping
+
+ if not copy_from_source:
+ # skip physx cloning, this means physx will walk and parse the stage one by one faithfully
+ cloner.newton_replicate(self.stage, *replicate_args)
+ cloner.usd_replicate(self.stage, *replicate_args, positions=self._default_env_origins)
def filter_collisions(self, global_prim_paths: list[str] | None = None):
"""Filter environments collisions.
@@ -263,7 +203,8 @@ def filter_collisions(self, global_prim_paths: list[str] | None = None):
self._global_prim_paths += global_prim_paths
# filter collisions within each environment instance
- self.cloner.filter_collisions(
+ cloner.filter_collisions(
+ self.stage,
self.physics_scene_path,
"/World/collisions",
self.env_prim_paths,
@@ -375,11 +316,11 @@ def surface_grippers(self) -> dict:
raise NotImplementedError("Surface grippers are not supported in IsaacLab for Newton.")
@property
- def extras(self) -> dict[str, XFormPrim]:
+ def extras(self) -> dict[str, Any]:
"""A dictionary of miscellaneous simulation objects that neither inherit from assets nor sensors.
- The keys are the names of the miscellaneous objects, and the values are the `XFormPrim`_
- of the corresponding prims.
+ The keys are the names of the miscellaneous objects, and the values are XFormPrim instances
+ from isaaclab.sim.prims.
As an example, lights or other props in the scene that do not have any attributes or properties that you
want to alter at runtime can be added to this dictionary.
@@ -387,9 +328,6 @@ def extras(self) -> dict[str, XFormPrim]:
Note:
These are not reset or updated by the scene. They are mainly other prims that are not necessarily
handled by the interactive scene, but are useful to be accessed by the user.
-
- .. _XFormPrim: https://docs.omniverse.nvidia.com/py/isaacsim/source/isaacsim.core/docs/index.html#isaacsim.core.prims.XFormPrim
-
"""
return self._extras
@@ -612,8 +550,6 @@ def _is_scene_setup_from_cfg(self) -> bool:
def _add_entities_from_cfg(self):
"""Add scene entities from the config."""
- # store paths that are in global collision filter
- self._global_prim_paths = list()
# parse the entire scene config and resolve regex
for asset_name, asset_cfg in self.cfg.__dict__.items():
# skip keywords
@@ -621,8 +557,19 @@ def _add_entities_from_cfg(self):
if asset_name in InteractiveSceneCfg.__dataclass_fields__ or asset_cfg is None:
continue
# resolve regex
+ require_clone = False
if hasattr(asset_cfg, "prim_path"):
- asset_cfg.prim_path = asset_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns)
+ # In order to compose cloner behavior more flexibly, we ask each spawner to spawn prototypes in
+ # prepared /World/template path, once all template is ready, cloner can determine what rules to follow
+ # to combine, and distribute the templates to cloned environments.
+ asset_cfg.prim_path = asset_cfg.prim_path.replace(self.env_regex_ns, "{ENV_REGEX_NS}")
+ destinations_regex_ns = asset_cfg.prim_path.format(ENV_REGEX_NS=self.env_regex_ns)
+ if self.env_regex_ns[:-2] in destinations_regex_ns:
+ require_clone = True
+ prototype_root = asset_cfg.prim_path.format(ENV_REGEX_NS=self.cloner_cfg.template_root)
+ asset_cfg.prim_path = f"{prototype_root}/{self.cloner_cfg.template_prototype_identifier}_.*"
+ else:
+ asset_cfg.prim_path = destinations_regex_ns
# create asset
if isinstance(asset_cfg, TerrainImporterCfg):
# terrains are special entities since they define environment origins
@@ -671,4 +618,18 @@ def _add_entities_from_cfg(self):
# store global collision paths
if hasattr(asset_cfg, "collision_group") and asset_cfg.collision_group == -1:
asset_paths = sim_utils.find_matching_prim_paths(asset_cfg.prim_path)
- self._global_prim_paths += asset_paths
+ if require_clone:
+ # we are going to clone this template path to actual cloned path, but we don't know which cloned
+ # paths it will end up, so add to temp self._global_template_prim_paths until final path resolved
+ self._global_template_prim_paths += asset_paths
+ else:
+ # we are not going to clone this path so directly add to s_global_prim_paths
+ self._global_prim_paths += asset_paths
+
+ if hasattr(asset_cfg, "prim_path") and require_clone:
+ # this allows on_prim_deletion is tied to the cloned path not template path
+ asset = self.__getitem__(asset_name)
+ if hasattr(asset, "cfg"):
+ asset.cfg.prim_path = destinations_regex_ns
+ if isinstance(asset, XFormPrim):
+ asset._regex_prim_paths = [destinations_regex_ns]
diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py
index 9ed37db5539..6a4e62000ec 100644
--- a/source/isaaclab/isaaclab/sensors/camera/camera.py
+++ b/source/isaaclab/isaaclab/sensors/camera/camera.py
@@ -12,17 +12,14 @@
from collections.abc import Sequence
from typing import TYPE_CHECKING, Any, Literal
-import carb
-import omni.kit.commands
-import omni.usd
-from isaacsim.core.prims import XFormPrim
-
# from isaacsim.core.version import get_version
from pxr import UsdGeom
import isaaclab.sim as sim_utils
import isaaclab.sim.utils.stage as stage_utils
import isaaclab.utils.sensors as sensor_utils
+from isaaclab.app.settings_manager import get_settings_manager
+from isaaclab.sim.prims import XFormPrim
from isaaclab.utils import to_camel_case
from isaaclab.utils.array import convert_to_torch
from isaaclab.utils.math import (
@@ -34,6 +31,10 @@
from ..sensor_base import SensorBase
from .camera_data import CameraData
+# import omni.usd
+# from isaacsim.core.prims import XFormPrim
+
+
if TYPE_CHECKING:
from .camera_cfg import CameraCfg
@@ -116,8 +117,8 @@ def __init__(self, cfg: CameraCfg):
# toggle rendering of rtx sensors as True
# this flag is read by SimulationContext to determine if rtx sensors should be rendered
- carb_settings_iface = carb.settings.get_settings()
- carb_settings_iface.set_bool("/isaaclab/render/rtx_sensors", True)
+ settings_manager = get_settings_manager()
+ settings_manager.set_bool("/isaaclab/render/rtx_sensors", True)
# spawn the asset
if self.cfg.spawn is not None:
@@ -260,6 +261,8 @@ def set_intrinsic_matrices(
# note: We have to do it this way because the camera might be on a different
# layer (default cameras are on session layer), and this is the simplest
# way to set the property on the right layer.
+ import omni.usd
+
omni.usd.set_prop_val(param_attr(), param_value)
# update the internal buffers
self._update_intrinsic_matrices(env_ids)
@@ -375,8 +378,8 @@ def _initialize_impl(self):
RuntimeError: If the number of camera prims in the view does not match the number of environments.
RuntimeError: If replicator was not found.
"""
- carb_settings_iface = carb.settings.get_settings()
- if not carb_settings_iface.get("/isaaclab/cameras_enabled"):
+ settings_manager = get_settings_manager()
+ if not settings_manager.get("/isaaclab/cameras_enabled"):
raise RuntimeError(
"A camera was spawned without the --enable_cameras flag. Please use --enable_cameras to enable"
" rendering."
diff --git a/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py b/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py
index a0600db4b11..9964f8f90c5 100644
--- a/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py
+++ b/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py
@@ -12,16 +12,56 @@
from collections.abc import Sequence
from typing import TYPE_CHECKING, Any
-import carb
import warp as wp
-from isaacsim.core.prims import XFormPrim
from pxr import UsdGeom
-from isaaclab.utils.warp.kernels import reshape_tiled_image
+from isaaclab.app.settings_manager import get_settings_manager
from ..sensor_base import SensorBase
from .camera import Camera
+
+def reshape_with_pytorch(
+ flat_buffer: torch.Tensor,
+ num_cameras: int,
+ height: int,
+ width: int,
+ num_channels: int,
+ num_tiles_x: int,
+) -> torch.Tensor:
+ """Reshapes a flattened tiled image buffer into a batch of images using PyTorch.
+
+ Args:
+ flat_buffer: The flattened input image buffer.
+ num_cameras: The number of cameras.
+ height: The height of each image.
+ width: The width of each image.
+ num_channels: The number of channels per pixel.
+ num_tiles_x: The number of tiles in x-direction.
+
+ Returns:
+ Batched images with shape (num_cameras, height, width, num_channels).
+ """
+ num_tiles_y = (num_cameras + num_tiles_x - 1) // num_tiles_x
+
+ # Reshape flat buffer to tiled image format: (tiled_height, tiled_width, num_channels)
+ tiled_height = num_tiles_y * height
+ tiled_width = num_tiles_x * width
+ tiled_image = flat_buffer.reshape(tiled_height, tiled_width, num_channels)
+
+ # Split into tiles along height, then width
+ # Result: (num_tiles_y, height, num_tiles_x, width, num_channels)
+ tiled_image = tiled_image.reshape(num_tiles_y, height, num_tiles_x, width, num_channels)
+
+ # Transpose to get (num_tiles_y, num_tiles_x, height, width, num_channels)
+ tiled_image = tiled_image.permute(0, 2, 1, 3, 4)
+
+ # Reshape to (num_tiles_y * num_tiles_x, height, width, num_channels)
+ batched_images = tiled_image.reshape(-1, height, width, num_channels)
+
+ return batched_images[:num_cameras]
+
+
if TYPE_CHECKING:
from .tiled_camera_cfg import TiledCameraCfg
@@ -83,6 +123,7 @@ def __init__(self, cfg: TiledCameraCfg):
RuntimeError: If Isaac Sim version < 4.2
ValueError: If the provided data types are not supported by the camera.
"""
+
super().__init__(cfg)
def __del__(self):
@@ -139,8 +180,8 @@ def _initialize_impl(self):
RuntimeError: If the number of camera prims in the view does not match the number of environments.
RuntimeError: If replicator was not found.
"""
- carb_settings_iface = carb.settings.get_settings()
- if not carb_settings_iface.get("/isaaclab/cameras_enabled"):
+ settings_manager = get_settings_manager()
+ if not settings_manager.get("/isaaclab/cameras_enabled"):
raise RuntimeError(
"A camera was spawned without the --enable_cameras flag. Please use --enable_cameras to enable"
" rendering."
@@ -151,6 +192,8 @@ def _initialize_impl(self):
# Initialize parent class
SensorBase._initialize_impl(self)
# Create a view for the sensor
+ from isaacsim.core.prims import XFormPrim
+
self._view = XFormPrim(self.cfg.prim_path, reset_xform_properties=False)
self._view.initialize()
# Check that sizes are correct
@@ -241,7 +284,9 @@ def _update_buffers_impl(self, env_ids: Sequence[int]):
# convert data buffer to warp array
if isinstance(tiled_data_buffer, np.ndarray):
- tiled_data_buffer = wp.array(tiled_data_buffer, device=self.device, dtype=wp.uint8)
+ # Let warp infer the dtype from numpy array instead of hardcoding uint8
+ # Different annotators return different dtypes: RGB(uint8), depth(float32), segmentation(uint32)
+ tiled_data_buffer = wp.array(tiled_data_buffer, device=self.device)
else:
tiled_data_buffer = tiled_data_buffer.to(device=self.device)
@@ -262,17 +307,16 @@ def _update_buffers_impl(self, env_ids: Sequence[int]):
if data_type == "motion_vectors":
tiled_data_buffer = tiled_data_buffer[:, :, :2].contiguous()
- wp.launch(
- kernel=reshape_tiled_image,
- dim=(self._view.count, self.cfg.height, self.cfg.width),
- inputs=[
- tiled_data_buffer.flatten(),
- wp.from_torch(self._data.output[data_type]), # zero-copy alias
- *list(self._data.output[data_type].shape[1:]), # height, width, num_channels
- self._tiling_grid_shape()[0], # num_tiles_x
- ],
- device=self.device,
- )
+ # Use torch to reshape tiled image buffer to batched image buffer
+ # Use PyTorch implementation for reshape
+ self._data.output[data_type][: self._view.count] = reshape_with_pytorch(
+ wp.to_torch(tiled_data_buffer.flatten()),
+ self._view.count,
+ self.cfg.height,
+ self.cfg.width,
+ self._data.output[data_type].shape[-1],
+ self._tiling_grid_shape()[0],
+ )[: self._view.count]
# alias rgb as first 3 channels of rgba
if data_type == "rgba" and "rgb" in self.cfg.data_types:
diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py
index e18621124c5..d2396368670 100644
--- a/source/isaaclab/isaaclab/sensors/sensor_base.py
+++ b/source/isaaclab/isaaclab/sensors/sensor_base.py
@@ -12,6 +12,7 @@
from __future__ import annotations
import builtins
+import contextlib
import inspect
import re
import torch
@@ -20,15 +21,16 @@
from collections.abc import Sequence
from typing import TYPE_CHECKING, Any
-import omni.kit.app
-import omni.timeline
-from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager
-
import isaaclab.sim as sim_utils
from isaaclab.sim import SimulationContext
from isaaclab.sim._impl.newton_manager import NewtonManager
from isaaclab.sim.utils.stage import get_current_stage
+# import omni.kit.app
+# import omni.timeline
+# from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager
+
+
if TYPE_CHECKING:
from .sensor_base_cfg import SensorBaseCfg
@@ -75,24 +77,24 @@ def safe_callback(callback_name, event, obj_ref):
# Object has been deleted; ignore.
pass
- # note: use weakref on callbacks to ensure that this object can be deleted when its destructor is called.
- # add callbacks for stage play/stop
- obj_ref = weakref.proxy(self)
- timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
-
- # the order is set to 10 which is arbitrary but should be lower priority than the default order of 0
- NewtonManager.add_on_start_callback(lambda: safe_callback("_initialize_callback", None, obj_ref))
- # register timeline STOP event callback (lower priority with order=10)
- self._invalidate_initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type(
- int(omni.timeline.TimelineEventType.STOP),
- lambda event, obj_ref=obj_ref: safe_callback("_invalidate_initialize_callback", event, obj_ref),
- order=10,
- )
- # register prim deletion callback
- self._prim_deletion_callback_id = SimulationManager.register_callback(
- lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref),
- event=IsaacEvents.PRIM_DELETION,
- )
+ # # note: use weakref on callbacks to ensure that this object can be deleted when its destructor is called.
+ # # add callbacks for stage play/stop
+ # obj_ref = weakref.proxy(self)
+ # timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
+
+ # # the order is set to 10 which is arbitrary but should be lower priority than the default order of 0
+ # NewtonManager.add_on_start_callback(lambda: safe_callback("_initialize_callback", None, obj_ref))
+ # # register timeline STOP event callback (lower priority with order=10)
+ # self._invalidate_initialize_handle = timeline_event_stream.create_subscription_to_pop_by_type(
+ # int(omni.timeline.TimelineEventType.STOP),
+ # lambda event, obj_ref=obj_ref: safe_callback("_invalidate_initialize_callback", event, obj_ref),
+ # order=10,
+ # )
+ # # register prim deletion callback
+ # self._prim_deletion_callback_id = SimulationManager.register_callback(
+ # lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref),
+ # event=IsaacEvents.PRIM_DELETION,
+ # )
# add handle for debug visualization (this is set to a valid handle inside set_debug_vis)
self._debug_vis_handle = None
@@ -101,8 +103,10 @@ def safe_callback(callback_name, event, obj_ref):
def __del__(self):
"""Unsubscribe from the callbacks."""
- # clear physics events handles
- self._clear_callbacks()
+ # Suppress errors during Python shutdown
+ with contextlib.suppress(ImportError, AttributeError, TypeError):
+ # clear physics events handles
+ self._clear_callbacks()
"""
Properties
@@ -181,6 +185,8 @@ def set_debug_vis(self, debug_vis: bool) -> bool:
if debug_vis:
# create a subscriber for the post update event if it doesn't exist
if self._debug_vis_handle is None:
+ import omni.kit.app
+
app_interface = omni.kit.app.get_app_interface()
self._debug_vis_handle = app_interface.get_post_update_event_stream().create_subscription_to_pop(
lambda event, obj=weakref.proxy(self): obj._debug_vis_callback(event)
@@ -319,14 +325,19 @@ def _on_prim_deletion(self, prim_path: str) -> None:
def _clear_callbacks(self) -> None:
"""Clears the callbacks."""
- if self._prim_deletion_callback_id:
- SimulationManager.deregister_callback(self._prim_deletion_callback_id)
+ import contextlib
+
+ if getattr(self, "_prim_deletion_callback_id", None):
+ with contextlib.suppress(ImportError, NameError):
+ from isaacsim.core.simulation_manager import SimulationManager
+
+ SimulationManager.deregister_callback(self._prim_deletion_callback_id)
self._prim_deletion_callback_id = None
- if self._invalidate_initialize_handle:
+ if getattr(self, "_invalidate_initialize_handle", None):
self._invalidate_initialize_handle.unsubscribe()
self._invalidate_initialize_handle = None
# clear debug visualization
- if self._debug_vis_handle:
+ if getattr(self, "_debug_vis_handle", None):
self._debug_vis_handle.unsubscribe()
self._debug_vis_handle = None
diff --git a/source/isaaclab/isaaclab/sim/__init__.py b/source/isaaclab/isaaclab/sim/__init__.py
index 6819cacf87b..c07a9d95cd3 100644
--- a/source/isaaclab/isaaclab/sim/__init__.py
+++ b/source/isaaclab/isaaclab/sim/__init__.py
@@ -26,7 +26,8 @@
"""
-from .converters import * # noqa: F401, F403
+# TODO: fix omni.kit.commands here
+# from .converters import * # noqa: F401, F403
from .schemas import * # noqa: F401, F403
from .simulation_cfg import RenderCfg, SimulationCfg # noqa: F401, F403
from .simulation_context import SimulationContext, build_simulation_context # noqa: F401, F403
diff --git a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py
index 096ed3b2b1d..1649409e7df 100644
--- a/source/isaaclab/isaaclab/sim/_impl/newton_manager.py
+++ b/source/isaaclab/isaaclab/sim/_impl/newton_manager.py
@@ -6,7 +6,6 @@
import numpy as np
import re
-import usdrt
import warp as wp
from newton import Axis, Contacts, Control, Model, ModelBuilder, State, eval_fk
from newton.sensors import ContactSensor as NewtonContactSensor
@@ -80,7 +79,11 @@ def clear(cls):
NewtonManager._on_init_callbacks = []
NewtonManager._on_start_callbacks = []
NewtonManager._usdrt_stage = None
- NewtonManager._cfg = NewtonCfg()
+ # Only create new config if not during Python shutdown
+ try:
+ NewtonManager._cfg = NewtonCfg()
+ except (ImportError, AttributeError, TypeError):
+ NewtonManager._cfg = None
NewtonManager._up_axis = "Z"
NewtonManager._first_call = True
@@ -125,6 +128,8 @@ def start_simulation(cls) -> None:
for callback in NewtonManager._on_start_callbacks:
callback()
if not NewtonManager._clone_physics_only:
+ import usdrt
+
NewtonManager._usdrt_stage = get_current_stage(fabric=True)
for i, prim_path in enumerate(NewtonManager._model.body_key):
prim = NewtonManager._usdrt_stage.GetPrimAtPath(prim_path)
@@ -136,10 +141,9 @@ def start_simulation(cls) -> None:
@classmethod
def instantiate_builder_from_stage(cls):
- import omni.usd
from pxr import UsdGeom
- stage = omni.usd.get_context().get_stage()
+ stage = get_current_stage()
up_axis = UsdGeom.GetStageUpAxis(stage)
builder = ModelBuilder(up_axis=up_axis)
builder.add_usd(stage)
diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py
index be7e18e8696..dbc883d4a5e 100644
--- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py
+++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py
@@ -7,15 +7,12 @@
import logging
import os
-import omni
-import omni.kit.commands
-from isaacsim.core.utils.extensions import enable_extension
from pxr import Gf, Tf, Usd, UsdGeom, UsdPhysics, UsdUtils
from isaaclab.sim.converters.asset_converter_base import AssetConverterBase
from isaaclab.sim.converters.mesh_converter_cfg import MeshConverterCfg
from isaaclab.sim.schemas import schemas
-from isaaclab.sim.utils import export_prim_to_file
+from isaaclab.sim.utils import create_default_xform_ops, export_prim_to_file
logger = logging.getLogger(__name__)
@@ -134,11 +131,10 @@ def _convert_asset(self, cfg: MeshConverterCfg):
)
# Delete the old Xform and make the new Xform the default prim
stage.SetDefaultPrim(xform_prim)
- # Apply default Xform rotation to mesh -> enable to set rotation and scale
- omni.kit.commands.execute(
- "CreateDefaultXformOnPrimCommand",
- prim_path=xform_prim.GetPath(),
- **{"stage": stage},
+
+ # Apply default Xform ops to xform_prim using utility function
+ create_default_xform_ops(
+ prim_path=xform_prim.GetPath(), stage=stage, xform_op_type="Scale, Orient, Translate", precision="Double"
)
# Apply translation, rotation, and scale to the Xform
@@ -169,9 +165,9 @@ def _convert_asset(self, cfg: MeshConverterCfg):
source_prim_path=geom_prim.GetPath(),
stage=stage,
)
- # Delete the original prim that will now be a reference
+ # Delete the original prim that will now be a reference using USD core API
geom_prim_path = geom_prim.GetPath().pathString
- omni.kit.commands.execute("DeletePrims", paths=[geom_prim_path], stage=stage)
+ stage.RemovePrim(geom_prim_path)
# Update references to exported Xform and make it instanceable
geom_undef_prim = stage.DefinePrim(geom_prim_path)
geom_undef_prim.GetReferences().AddReference(self.usd_instanceable_meshes_path, primPath=geom_prim_path)
@@ -215,6 +211,8 @@ async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool
Returns:
True if the conversion succeeds.
"""
+ from isaacsim.core.utils.extensions import enable_extension
+
enable_extension("omni.kit.asset_converter")
import omni.kit.asset_converter
diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py
index 321fbe00b0c..1e6da45c189 100644
--- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py
+++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py
@@ -7,10 +7,6 @@
import os
-import isaacsim
-import omni.kit.commands
-import omni.usd
-
from .asset_converter_base import AssetConverterBase
from .mjcf_converter_cfg import MjcfConverterCfg
@@ -55,6 +51,8 @@ def _convert_asset(self, cfg: MjcfConverterCfg):
Args:
cfg: The configuration instance for MJCF to USD conversion.
"""
+ import omni.kit.commands
+
import_config = self._get_mjcf_import_config()
file_basename, _ = os.path.basename(cfg.asset_path).split(".")
omni.kit.commands.execute(
@@ -65,13 +63,15 @@ def _convert_asset(self, cfg: MjcfConverterCfg):
prim_path=f"/{file_basename}",
)
- def _get_mjcf_import_config(self) -> isaacsim.asset.importer.mjcf.ImportConfig:
+ def _get_mjcf_import_config(self):
"""Returns the import configuration for MJCF to USD conversion.
Returns:
The constructed ``ImportConfig`` object containing the desired settings.
"""
+ import omni.kit.commands
+
_, import_config = omni.kit.commands.execute("MJCFCreateImportConfig")
# set the unit scaling factor, 1.0 means meters, 100.0 means cm
diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py
index c5bf667130e..bdd619b1a70 100644
--- a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py
+++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py
@@ -8,12 +8,6 @@
import math
import re
-import isaacsim
-import omni.kit.app
-import omni.kit.commands
-import omni.usd
-from isaacsim.core.utils.extensions import enable_extension
-
from .asset_converter_base import AssetConverterBase
from .urdf_converter_cfg import UrdfConverterCfg
@@ -46,6 +40,11 @@ def __init__(self, cfg: UrdfConverterCfg):
Args:
cfg: The configuration instance for URDF to USD conversion.
"""
+ import omni.kit.app
+ import omni.kit.commands # noqa: F401
+ import omni.usd # noqa: F401
+ from isaacsim.core.utils.extensions import enable_extension
+
manager = omni.kit.app.get_app().get_extension_manager()
if not manager.is_extension_enabled("isaacsim.asset.importer.urdf"):
enable_extension("isaacsim.asset.importer.urdf")
@@ -65,6 +64,8 @@ def _convert_asset(self, cfg: UrdfConverterCfg):
cfg: The URDF conversion configuration.
"""
+ import omni.kit.commands
+
import_config = self._get_urdf_import_config()
# parse URDF file
result, self._robot_model = omni.kit.commands.execute(
@@ -81,6 +82,8 @@ def _convert_asset(self, cfg: UrdfConverterCfg):
self._robot_model.root_link = cfg.root_link_name
# convert the model to USD
+ import omni.kit.commands
+
omni.kit.commands.execute(
"URDFImportRobot",
urdf_path=cfg.asset_path,
@@ -95,12 +98,14 @@ def _convert_asset(self, cfg: UrdfConverterCfg):
Helper methods.
"""
- def _get_urdf_import_config(self) -> isaacsim.asset.importer.urdf.ImportConfig:
+ def _get_urdf_import_config(self):
"""Create and fill URDF ImportConfig with desired settings
Returns:
The constructed ``ImportConfig`` object containing the desired settings.
"""
+ import omni.kit.commands
+
# create a new import config
_, import_config = omni.kit.commands.execute("URDFCreateImportConfig")
diff --git a/source/isaaclab/isaaclab/sim/prims/__init__.py b/source/isaaclab/isaaclab/sim/prims/__init__.py
new file mode 100644
index 00000000000..22ff05c4e40
--- /dev/null
+++ b/source/isaaclab/isaaclab/sim/prims/__init__.py
@@ -0,0 +1,10 @@
+# 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
+
+"""Sub-module for USD prim wrappers using pure USD core APIs."""
+
+from .xform_prim import XFormPrim
+
+__all__ = ["XFormPrim"]
diff --git a/source/isaaclab/isaaclab/sim/prims/xform_prim.py b/source/isaaclab/isaaclab/sim/prims/xform_prim.py
new file mode 100644
index 00000000000..ec9cee45557
--- /dev/null
+++ b/source/isaaclab/isaaclab/sim/prims/xform_prim.py
@@ -0,0 +1,560 @@
+# 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
+
+"""Xform prim wrapper using USD core APIs.
+
+This module provides a pure USD implementation of XFormPrim that doesn't depend on
+Isaac Sim or Omniverse-specific APIs. It supports multiple prims (views) using regex patterns.
+"""
+
+from __future__ import annotations
+
+import logging
+import numpy as np
+import re
+import torch
+from collections.abc import Sequence
+
+from pxr import Gf, Usd, UsdGeom
+
+from isaaclab.sim.utils.stage import get_current_stage
+
+logger = logging.getLogger(__name__)
+
+
+class XFormPrim:
+ """Wrapper around USD Xformable prims for managing transformations.
+
+ This class provides a simplified interface for working with one or more USD Xformable prims,
+ handling transformations (translation, rotation, scale) using pure USD core APIs.
+ It supports regex patterns to match multiple prims.
+
+ Args:
+ prim_paths_expr: Prim path or regex pattern to match prims. Can also be a list of paths/patterns.
+ Example: "/World/Env[1-5]/Robot" will match /World/Env1/Robot, /World/Env2/Robot, etc.
+ name: Optional name for this view. Defaults to "xform_prim_view".
+ positions: Optional initial world positions (N, 3) or (3,).
+ translations: Optional initial local translations (N, 3) or (3,).
+ orientations: Optional initial orientations as quaternions (N, 4) or (4,), in (w,x,y,z) format.
+ scales: Optional initial scales (N, 3) or (3,).
+ reset_xform_properties: If True, resets transform properties to canonical set. Defaults to True.
+ stage: The USD stage. If None, will get the current stage.
+
+ Raises:
+ ValueError: If no prims match the provided path expression.
+ ValueError: If both positions and translations are specified.
+ """
+
+ def __init__(
+ self,
+ prim_paths_expr: str | list[str],
+ name: str = "xform_prim_view",
+ positions: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ translations: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ orientations: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ scales: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ reset_xform_properties: bool = True,
+ stage: Usd.Stage | None = None,
+ ):
+ """Initialize the XFormPrim wrapper."""
+ self._name = name
+ self._stage = stage if stage is not None else get_current_stage()
+
+ # Convert to list if single string
+ if not isinstance(prim_paths_expr, list):
+ prim_paths_expr = [prim_paths_expr]
+
+ # Resolve regex patterns to actual prim paths
+ self._prim_paths = self._resolve_prim_paths(prim_paths_expr)
+
+ if not self._prim_paths:
+ raise ValueError(f"No prims found matching patterns: {prim_paths_expr}")
+
+ # Get all prims
+ self._prims = [self._stage.GetPrimAtPath(path) for path in self._prim_paths]
+ self._count = len(self._prims)
+
+ # Validate all prims
+ for i, prim in enumerate(self._prims):
+ if not prim.IsValid():
+ raise ValueError(f"Invalid prim at path: {self._prim_paths[i]}")
+
+ # Reset xform properties if requested
+ if reset_xform_properties:
+ self._set_xform_properties()
+
+ # Check for conflicting arguments
+ if translations is not None and positions is not None:
+ raise ValueError("Cannot specify both translations and positions")
+
+ # Apply initial transformations if provided
+ if positions is not None or translations is not None or orientations is not None:
+ if translations is not None:
+ self.set_local_poses(translations, orientations)
+ else:
+ self.set_world_poses(positions, orientations)
+
+ if scales is not None:
+ self.set_local_scales(scales)
+
+ def _resolve_prim_paths(self, patterns: list[str]) -> list[str]:
+ """Resolve regex patterns to actual prim paths.
+
+ Args:
+ patterns: List of prim path patterns (can include regex).
+
+ Returns:
+ List of resolved prim paths.
+ """
+ resolved_paths = []
+
+ for pattern in patterns:
+ # Check if pattern contains regex characters
+ if re.search(r"[\[\]\*\?\|]", pattern):
+ # Convert USD-style regex to Python regex
+ # [1-5] stays as is, .* for wildcard
+ regex_pattern = pattern.replace(".", r"\.") # Escape dots
+ regex_pattern = regex_pattern.replace("*", ".*") # * becomes .*
+ regex_pattern = f"^{regex_pattern}$"
+
+ # Search through all prims
+ for prim in self._stage.Traverse():
+ prim_path = str(prim.GetPath())
+ if re.match(regex_pattern, prim_path):
+ if prim.IsA(UsdGeom.Xformable) or prim.IsA(UsdGeom.Xform):
+ resolved_paths.append(prim_path)
+ else:
+ # Direct path, just add it
+ resolved_paths.append(pattern)
+
+ # Remove duplicates while preserving order
+ seen = set()
+ unique_paths = []
+ for path in resolved_paths:
+ if path not in seen:
+ seen.add(path)
+ unique_paths.append(path)
+
+ return unique_paths
+
+ @property
+ def count(self) -> int:
+ """Get the number of prims in this view."""
+ return self._count
+
+ @property
+ def prim_paths(self) -> list[str]:
+ """Get list of all prim paths in this view."""
+ return self._prim_paths.copy()
+
+ @property
+ def name(self) -> str:
+ """Get the name of this view."""
+ return self._name
+
+ def initialize(self) -> None:
+ """Initialize the prims (compatibility method).
+
+ This method is provided for compatibility with Isaac Sim's XFormPrim interface.
+ For pure USD implementation, initialization happens in __init__.
+ """
+ pass
+
+ def _set_xform_properties(self) -> None:
+ """Set xform properties to the canonical set: translate, orient, scale.
+
+ This removes any non-standard rotation properties and ensures all prims
+ have the standard xform operations in the correct order.
+ """
+ # Get current poses to restore after modifying xform ops
+ current_positions, current_orientations = self.get_world_poses()
+
+ # Properties to remove (non-standard rotation ops and transforms)
+ properties_to_remove = [
+ "xformOp:rotateX",
+ "xformOp:rotateXZY",
+ "xformOp:rotateY",
+ "xformOp:rotateYXZ",
+ "xformOp:rotateYZX",
+ "xformOp:rotateZ",
+ "xformOp:rotateZYX",
+ "xformOp:rotateZXY",
+ "xformOp:rotateXYZ",
+ "xformOp:transform",
+ ]
+
+ for i in range(self._count):
+ prim = self._prims[i]
+ prop_names = prim.GetPropertyNames()
+ xformable = UsdGeom.Xformable(prim)
+ xformable.ClearXformOpOrder()
+
+ # Remove non-standard properties
+ for prop_name in prop_names:
+ if prop_name in properties_to_remove:
+ prim.RemoveProperty(prop_name)
+
+ # Set up scale op
+ if "xformOp:scale" not in prop_names:
+ xform_op_scale = xformable.AddXformOp(UsdGeom.XformOp.TypeScale, UsdGeom.XformOp.PrecisionDouble, "")
+ xform_op_scale.Set(Gf.Vec3d(1.0, 1.0, 1.0))
+ else:
+ xform_op_scale = UsdGeom.XformOp(prim.GetAttribute("xformOp:scale"))
+
+ # Handle unitsResolve scale factor if present
+ if "xformOp:scale:unitsResolve" in prop_names:
+ current_scale = np.array(prim.GetAttribute("xformOp:scale").Get())
+ units_scale = np.array(prim.GetAttribute("xformOp:scale:unitsResolve").Get())
+ new_scale = current_scale * units_scale
+ # Convert to Python floats for USD
+ prim.GetAttribute("xformOp:scale").Set(
+ Gf.Vec3d(float(new_scale[0]), float(new_scale[1]), float(new_scale[2]))
+ )
+ prim.RemoveProperty("xformOp:scale:unitsResolve")
+
+ # Set up translate op
+ if "xformOp:translate" not in prop_names:
+ xform_op_translate = xformable.AddXformOp(
+ UsdGeom.XformOp.TypeTranslate, UsdGeom.XformOp.PrecisionDouble, ""
+ )
+ else:
+ xform_op_translate = UsdGeom.XformOp(prim.GetAttribute("xformOp:translate"))
+
+ # Set up orient (quaternion rotation) op
+ if "xformOp:orient" not in prop_names:
+ xform_op_rot = xformable.AddXformOp(UsdGeom.XformOp.TypeOrient, UsdGeom.XformOp.PrecisionDouble, "")
+ else:
+ xform_op_rot = UsdGeom.XformOp(prim.GetAttribute("xformOp:orient"))
+
+ # Set the xform op order: translate, orient, scale
+ xformable.SetXformOpOrder([xform_op_translate, xform_op_rot, xform_op_scale])
+
+ # Restore the original poses
+ self.set_world_poses(positions=current_positions, orientations=current_orientations)
+
+ def _to_numpy(self, value: torch.Tensor | np.ndarray | Sequence[float] | None) -> np.ndarray | None:
+ """Convert input to numpy array."""
+ if value is None:
+ return None
+ if isinstance(value, torch.Tensor):
+ return value.detach().cpu().numpy()
+ elif isinstance(value, np.ndarray):
+ return value
+ else:
+ return np.array(value)
+
+ def set_world_poses(
+ self,
+ positions: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ orientations: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> None:
+ """Set world poses of the prims.
+
+ Args:
+ positions: World positions (N, 3) or (3,). If None, positions are not changed.
+ orientations: World orientations as quaternions (N, 4) or (4,), in (w,x,y,z) format.
+ If None, orientations are not changed.
+ indices: Indices of prims to update. If None, all prims are updated.
+ """
+ # Convert to numpy
+ pos_np = self._to_numpy(positions)
+ orient_np = self._to_numpy(orientations)
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to update
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ # Broadcast if needed
+ if pos_np is not None:
+ if pos_np.ndim == 1:
+ pos_np = np.tile(pos_np, (len(prim_indices), 1))
+
+ if orient_np is not None:
+ if orient_np.ndim == 1:
+ orient_np = np.tile(orient_np, (len(prim_indices), 1))
+
+ # Update each prim
+ for idx, prim_idx in enumerate(prim_indices):
+ prim = self._prims[prim_idx]
+ xformable = UsdGeom.Xformable(prim)
+
+ # Get or create the translate op
+ translate_attr = prim.GetAttribute("xformOp:translate")
+ if translate_attr:
+ translate_op = UsdGeom.XformOp(translate_attr)
+ else:
+ translate_op = xformable.AddXformOp(UsdGeom.XformOp.TypeTranslate, UsdGeom.XformOp.PrecisionDouble)
+
+ # Get or create the orient op
+ orient_attr = prim.GetAttribute("xformOp:orient")
+ if orient_attr:
+ orient_op = UsdGeom.XformOp(orient_attr)
+ else:
+ orient_op = xformable.AddXformOp(UsdGeom.XformOp.TypeOrient, UsdGeom.XformOp.PrecisionDouble)
+
+ # Set position
+ if pos_np is not None:
+ # Convert numpy values to Python floats for USD
+ translate_op.Set(Gf.Vec3d(float(pos_np[idx, 0]), float(pos_np[idx, 1]), float(pos_np[idx, 2])))
+
+ # Set orientation
+ if orient_np is not None:
+ # Convert numpy values to Python floats for USD
+ w = float(orient_np[idx, 0])
+ x = float(orient_np[idx, 1])
+ y = float(orient_np[idx, 2])
+ z = float(orient_np[idx, 3])
+ quat = Gf.Quatd(w, Gf.Vec3d(x, y, z))
+ orient_op.Set(quat)
+
+ def set_local_poses(
+ self,
+ translations: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ orientations: torch.Tensor | np.ndarray | Sequence[float] | None = None,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> None:
+ """Set local poses of the prims (relative to parent).
+
+ Args:
+ translations: Local translations (N, 3) or (3,).
+ orientations: Local orientations as quaternions (N, 4) or (4,), in (w,x,y,z) format.
+ indices: Indices of prims to update. If None, all prims are updated.
+ """
+ # For local poses, we use the same method since USD xform ops are inherently local
+ self.set_world_poses(positions=translations, orientations=orientations, indices=indices)
+
+ def set_local_scales(
+ self,
+ scales: torch.Tensor | np.ndarray | Sequence[float],
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> None:
+ """Set local scales of the prims.
+
+ Args:
+ scales: Scale factors (N, 3) or (3,).
+ indices: Indices of prims to update. If None, all prims are updated.
+ """
+ scales_np = self._to_numpy(scales)
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to update
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ # Broadcast if needed
+ if scales_np.ndim == 1:
+ scales_np = np.tile(scales_np, (len(prim_indices), 1))
+
+ # Update each prim
+ for idx, prim_idx in enumerate(prim_indices):
+ prim = self._prims[prim_idx]
+ scale_attr = prim.GetAttribute("xformOp:scale")
+ if scale_attr:
+ # Convert numpy values to Python floats for USD
+ scale_attr.Set(Gf.Vec3d(float(scales_np[idx, 0]), float(scales_np[idx, 1]), float(scales_np[idx, 2])))
+
+ def get_world_poses(
+ self,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> tuple[np.ndarray, np.ndarray]:
+ """Get world poses of the prims.
+
+ Args:
+ indices: Indices of prims to query. If None, all prims are queried.
+
+ Returns:
+ A tuple of (positions, orientations) where:
+ - positions is a (N, 3) numpy array
+ - orientations is a (N, 4) numpy array in (w,x,y,z) format
+ """
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to query
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ positions = []
+ orientations = []
+
+ for prim_idx in prim_indices:
+ prim = self._prims[prim_idx]
+ xformable = UsdGeom.Xformable(prim)
+
+ # Get world transform matrix
+ xform_matrix = xformable.ComputeLocalToWorldTransform(Usd.TimeCode.Default())
+
+ # Extract translation
+ translation = xform_matrix.ExtractTranslation()
+ positions.append([translation[0], translation[1], translation[2]])
+
+ # Extract rotation as quaternion
+ rotation = xform_matrix.ExtractRotation()
+ quat = rotation.GetQuat()
+ # USD uses (real, i, j, k) which is (w, x, y, z)
+ orientations.append(
+ [quat.GetReal(), quat.GetImaginary()[0], quat.GetImaginary()[1], quat.GetImaginary()[2]]
+ )
+
+ return np.array(positions, dtype=np.float32), np.array(orientations, dtype=np.float32)
+
+ def get_local_poses(
+ self,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> tuple[np.ndarray, np.ndarray]:
+ """Get local poses of the prims (relative to parent).
+
+ Args:
+ indices: Indices of prims to query. If None, all prims are queried.
+
+ Returns:
+ A tuple of (translations, orientations) where:
+ - translations is a (N, 3) numpy array
+ - orientations is a (N, 4) numpy array in (w,x,y,z) format
+ """
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to query
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ translations = []
+ orientations = []
+
+ for prim_idx in prim_indices:
+ prim = self._prims[prim_idx]
+
+ # Get local transform operations
+ translate_attr = prim.GetAttribute("xformOp:translate")
+ orient_attr = prim.GetAttribute("xformOp:orient")
+
+ # Get translation
+ if translate_attr:
+ trans = translate_attr.Get()
+ translations.append([trans[0], trans[1], trans[2]])
+ else:
+ translations.append([0.0, 0.0, 0.0])
+
+ # Get orientation
+ if orient_attr:
+ quat = orient_attr.Get()
+ # USD quaternion is (real, i, j, k) which is (w, x, y, z)
+ orientations.append(
+ [quat.GetReal(), quat.GetImaginary()[0], quat.GetImaginary()[1], quat.GetImaginary()[2]]
+ )
+ else:
+ orientations.append([1.0, 0.0, 0.0, 0.0])
+
+ return np.array(translations, dtype=np.float32), np.array(orientations, dtype=np.float32)
+
+ def get_local_scales(
+ self,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> np.ndarray:
+ """Get local scales of the prims.
+
+ Args:
+ indices: Indices of prims to query. If None, all prims are queried.
+
+ Returns:
+ A (N, 3) numpy array of scale factors.
+ """
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to query
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ scales = []
+
+ for prim_idx in prim_indices:
+ prim = self._prims[prim_idx]
+ scale_attr = prim.GetAttribute("xformOp:scale")
+
+ if scale_attr:
+ scale = scale_attr.Get()
+ scales.append([scale[0], scale[1], scale[2]])
+ else:
+ scales.append([1.0, 1.0, 1.0])
+
+ return np.array(scales, dtype=np.float32)
+
+ def set_visibilities(
+ self,
+ visibilities: np.ndarray | torch.Tensor | list,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> None:
+ """Set visibilities of the prims.
+
+ Args:
+ visibilities: Boolean array indicating visibility (N,).
+ indices: Indices of prims to update. If None, all prims are updated.
+ """
+ visibilities_np = self._to_numpy(visibilities)
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to update
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ # Broadcast if needed
+ if visibilities_np.ndim == 0 or len(visibilities_np) == 1:
+ visibilities_np = np.full(len(prim_indices), visibilities_np.item())
+
+ # Update each prim
+ for idx, prim_idx in enumerate(prim_indices):
+ prim = self._prims[prim_idx]
+ imageable = UsdGeom.Imageable(prim)
+ if visibilities_np[idx]:
+ imageable.MakeVisible()
+ else:
+ imageable.MakeInvisible()
+
+ def get_visibilities(
+ self,
+ indices: np.ndarray | list | torch.Tensor | None = None,
+ ) -> np.ndarray:
+ """Get visibilities of the prims.
+
+ Args:
+ indices: Indices of prims to query. If None, all prims are queried.
+
+ Returns:
+ Boolean array indicating visibility (N,).
+ """
+ indices_np = self._to_numpy(indices)
+
+ # Determine which prims to query
+ if indices_np is None:
+ prim_indices = range(self._count)
+ else:
+ prim_indices = indices_np.astype(int)
+
+ visibilities = []
+
+ for prim_idx in prim_indices:
+ prim = self._prims[prim_idx]
+ imageable = UsdGeom.Imageable(prim)
+ is_visible = imageable.ComputeVisibility(Usd.TimeCode.Default()) != UsdGeom.Tokens.invisible
+ visibilities.append(is_visible)
+
+ return np.array(visibilities, dtype=bool)
+
+ def __repr__(self) -> str:
+ """Return string representation."""
+ return f"XFormPrim(name='{self._name}', count={self._count})"
diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py
index 536c9574674..f4aaa4720c6 100644
--- a/source/isaaclab/isaaclab/sim/schemas/schemas.py
+++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py
@@ -9,8 +9,8 @@
import logging
import math
-import omni.physx.scripts.utils as physx_utils
-from omni.physx.scripts import deformableUtils as deformable_utils
+# import omni.physx.scripts.utils as physx_utils
+# from omni.physx.scripts import deformableUtils as deformable_utils
from pxr import Usd, UsdPhysics
from isaaclab.sim.utils.stage import get_current_stage
@@ -162,7 +162,8 @@ def modify_articulation_root_properties(
)
# create a fixed joint between the root link and the world frame
- physx_utils.createJoint(stage=stage, joint_type="Fixed", from_prim=None, to_prim=articulation_prim)
+ # physx_utils.createJoint(stage=stage, joint_type="Fixed", from_prim=None, to_prim=articulation_prim)
+ # TODO: fix this
# Having a fixed joint on a rigid body is not treated as "fixed base articulation".
# instead, it is treated as a part of the maximal coordinate tree.
@@ -914,6 +915,8 @@ def modify_deformable_body_properties(
# convert to dict
cfg = cfg.to_dict()
# set into deformable body API
+ from omni.physx.scripts import deformableUtils as deformable_utils
+
attr_kwargs = {
attr_name: cfg.pop(attr_name)
for attr_name in [
diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py
index f2c0ad16864..8dc2e656aca 100644
--- a/source/isaaclab/isaaclab/sim/simulation_context.py
+++ b/source/isaaclab/isaaclab/sim/simulation_context.py
@@ -11,23 +11,25 @@
import toml
import torch
import traceback
-import weakref
from collections.abc import Iterator
from contextlib import contextmanager
from typing import Any
-import carb
import flatdict
-import omni.physx
-import omni.usd
-from isaacsim.core.api.simulation_context import SimulationContext as _SimulationContext
-from isaacsim.core.simulation_manager import SimulationManager
-from isaacsim.core.utils.viewports import set_camera_view
-from isaacsim.core.version import get_version
-from omni.physics.stageupdate import get_physics_stage_update_node_interface
-from pxr import Usd
+
+# import omni.physx
+# import omni.usd
+# from isaacsim.core.api.simulation_context import SimulationContext as _SimulationContext
+# from isaacsim.core.simulation_manager import SimulationManager
+# from isaacsim.core.utils.viewports import set_camera_view
+# from isaacsim.core.version import get_version
+# from omni.physics.stageupdate import get_physics_stage_update_node_interface
+from pxr import Usd, UsdUtils
import isaaclab.sim.utils.stage as stage_utils
+
+# Import settings manager for both Omniverse and standalone modes
+from isaaclab.app.settings_manager import SettingsManager
from isaaclab.sim._impl.newton_manager import NewtonManager
from isaaclab.sim.utils import create_new_stage_in_memory, use_stage
from isaaclab.visualizers import NewtonVisualizerCfg, OVVisualizerCfg, RerunVisualizerCfg, Visualizer
@@ -41,7 +43,7 @@
logger = logging.getLogger(__name__)
-class SimulationContext(_SimulationContext):
+class SimulationContext:
"""A class to control simulation-related events such as physics stepping and rendering.
The simulation context helps control various simulation aspects. This includes:
@@ -51,15 +53,13 @@ class SimulationContext(_SimulationContext):
* playing, pausing, stepping and stopping the simulation
* adding and removing callbacks to different simulation events such as physics stepping, rendering, etc.
- This class inherits from the :class:`isaacsim.core.api.simulation_context.SimulationContext` class and
- adds additional functionalities such as setting up the simulation context with a configuration object,
- exposing other commonly used simulator-related functions, and performing version checks of Isaac Sim
- to ensure compatibility between releases.
+ This class implements a singleton pattern to ensure only one simulation context exists at a time.
+ The singleton instance can be accessed using the ``instance()`` class method.
The simulation context is a singleton object. This means that there can only be one instance
- of the simulation context at any given time. This is enforced by the parent class. Therefore, it is
- not possible to create multiple instances of the simulation context. Instead, the simulation context
- can be accessed using the ``instance()`` method.
+ of the simulation context at any given time. Therefore, it is not possible to create multiple
+ instances of the simulation context. Instead, the simulation context can be accessed using the
+ ``instance()`` method.
.. attention::
Since we only support the `PyTorch `_ backend for simulation, the
@@ -82,6 +82,9 @@ class SimulationContext(_SimulationContext):
the non-``_async`` functions are used in the standalone python script mode.
"""
+ # Singleton instance
+ _instance: "SimulationContext | None" = None
+
class RenderMode(enum.IntEnum):
"""Different rendering modes for the simulation.
@@ -117,6 +120,29 @@ class RenderMode(enum.IntEnum):
FULL_RENDERING = 2
"""Full rendering, where all the simulation viewports, cameras and UI elements are updated."""
+ def __new__(cls, cfg: SimulationCfg | None = None):
+ """Enforce singleton pattern by returning existing instance if available.
+
+ Args:
+ cfg: The configuration of the simulation. Ignored if instance already exists.
+
+ Returns:
+ The singleton instance of SimulationContext.
+ """
+ if cls._instance is None:
+ cls._instance = super().__new__(cls)
+ cls._instance._initialized = False
+ return cls._instance
+
+ @classmethod
+ def instance(cls) -> "SimulationContext | None":
+ """Get the singleton instance of the simulation context.
+
+ Returns:
+ The singleton instance if it exists, None otherwise.
+ """
+ return cls._instance
+
def __init__(self, cfg: SimulationCfg | None = None):
"""Creates a simulation context to control the simulator.
@@ -124,55 +150,74 @@ def __init__(self, cfg: SimulationCfg | None = None):
cfg: The configuration of the simulation. Defaults to None,
in which case the default configuration is used.
"""
+ # Skip initialization if already initialized (singleton pattern)
+ if self._initialized:
+ return
+
# store input
if cfg is None:
cfg = SimulationCfg()
# check that the config is valid
cfg.validate()
self.cfg = cfg
- # check that simulation is running
- if stage_utils.get_current_stage() is None:
- raise RuntimeError("The stage has not been created. Did you run the simulator?")
- # create stage in memory if requested
+ # create or get stage using USD core APIs
if self.cfg.create_stage_in_memory:
+ # Create new stage in memory using USD core API
self._initial_stage = create_new_stage_in_memory()
else:
- self._initial_stage = omni.usd.get_context().get_stage()
+ # Try to get existing stage from USD StageCache
+ stage_cache = UsdUtils.StageCache.Get()
+ if stage_cache.Size() > 0:
+ all_stages = stage_cache.GetAllStages()
+ if all_stages:
+ self._initial_stage = all_stages[0]
+ else:
+ raise RuntimeError("No USD stage found in StageCache. Please create a stage first.")
+ else:
+ # No stage exists, try omni.usd as fallback
+ try:
+ import omni.usd
+
+ self._initial_stage = omni.usd.get_context().get_stage()
+ except (ImportError, AttributeError):
+ # if we need to create a new stage outside of omni.usd, we have to do it in memory with USD core APIs
+ self._initial_stage = create_new_stage_in_memory()
+ # raise RuntimeError("No USD stage is currently open. Please create a stage first.")
+
+ # Store stage reference for easy access
+ self.stage = self._initial_stage
# acquire settings interface
- self.carb_settings = carb.settings.get_settings()
+ # Use settings manager (works in both Omniverse and standalone modes)
+ self.settings = SettingsManager.instance()
# apply carb physics settings
- SimulationManager._clear()
+ # SimulationManager._clear()
self._apply_physics_settings()
# note: we read this once since it is not expected to change during runtime
# read flag for whether a local GUI is enabled
self._local_gui = (
- self.carb_settings.get("/app/window/enabled")
- if self.carb_settings.get("/app/window/enabled") is not None
- else False
+ self.settings.get("/app/window/enabled") if self.settings.get("/app/window/enabled") is not None else False
)
# read flag for whether livestreaming GUI is enabled
self._livestream_gui = (
- self.carb_settings.get("/app/livestream/enabled")
- if self.carb_settings.get("/app/livestream/enabled") is not None
+ self.settings.get("/app/livestream/enabled")
+ if self.settings.get("/app/livestream/enabled") is not None
else False
)
# read flag for whether XR GUI is enabled
self._xr_gui = (
- self.carb_settings.get("/app/xr/enabled")
- if self.carb_settings.get("/app/xr/enabled") is not None
- else False
+ self.settings.get("/app/xr/enabled") if self.settings.get("/app/xr/enabled") is not None else False
)
# read flag for whether the Isaac Lab viewport capture pipeline will be used,
# casting None to False if the flag doesn't exist
# this flag is set from the AppLauncher class
- self._offscreen_render = bool(self.carb_settings.get("/isaaclab/render/offscreen"))
+ self._offscreen_render = bool(self.settings.get("/isaaclab/render/offscreen"))
# read flag for whether the default viewport should be enabled
- self._render_viewport = bool(self.carb_settings.get("/isaaclab/render/active_viewport"))
+ self._render_viewport = bool(self.settings.get("/isaaclab/render/active_viewport"))
# flag for whether any GUI will be rendered (local, livestreamed or viewport)
self._has_gui = self._local_gui or self._livestream_gui or self._xr_gui
@@ -232,7 +277,7 @@ def __init__(self, cfg: SimulationCfg | None = None):
self._fabric_iface = None
# read isaac sim version (this includes build tag, release tag etc.)
# note: we do it once here because it reads the VERSION file from disk and is not expected to change.
- self._isaacsim_version = get_version()
+ # self._isaacsim_version = get_version()
# create a tensor for gravity
# note: this line is needed to create a "tensor" in the device to avoid issues with torch 2.1 onwards.
@@ -243,17 +288,17 @@ def __init__(self, cfg: SimulationCfg | None = None):
# define a global variable to store the exceptions raised in the callback stack
builtins.ISAACLAB_CALLBACK_EXCEPTION = None
- # add callback to deal the simulation app when simulation is stopped.
- # this is needed because physics views go invalid once we stop the simulation
- if not builtins.ISAAC_LAUNCHED_FROM_TERMINAL:
- timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
- self._app_control_on_stop_handle = timeline_event_stream.create_subscription_to_pop_by_type(
- int(omni.timeline.TimelineEventType.STOP),
- lambda *args, obj=weakref.proxy(self): obj._app_control_on_stop_handle_fn(*args),
- order=15,
- )
- else:
- self._app_control_on_stop_handle = None
+ # # add callback to deal the simulation app when simulation is stopped.
+ # # this is needed because physics views go invalid once we stop the simulation
+ # if not builtins.ISAAC_LAUNCHED_FROM_TERMINAL:
+ # timeline_event_stream = omni.timeline.get_timeline_interface().get_timeline_event_stream()
+ # self._app_control_on_stop_handle = timeline_event_stream.create_subscription_to_pop_by_type(
+ # int(omni.timeline.TimelineEventType.STOP),
+ # lambda *args, obj=weakref.proxy(self): obj._app_control_on_stop_handle_fn(*args),
+ # order=15,
+ # )
+ # else:
+ # self._app_control_on_stop_handle = None
self._disable_app_control_on_stop_handle = False
# initialize visualizers and scene data provider
@@ -270,45 +315,65 @@ def __init__(self, cfg: SimulationCfg | None = None):
if "newton_cfg" in sim_params:
newton_params = sim_params.pop("newton_cfg")
- # create a simulation context to control the simulator
- if float(".".join(self._isaacsim_version[2])) < 5:
- # stage arg is not supported before isaac sim 5.0
- super().__init__(
- stage_units_in_meters=1.0,
- physics_dt=self.cfg.dt,
- rendering_dt=self.cfg.dt * self.cfg.render_interval,
- backend="torch",
- sim_params=sim_params,
- physics_prim_path=self.cfg.physics_prim_path,
- device=self.cfg.device,
- )
- else:
- super().__init__(
- stage_units_in_meters=1.0,
- physics_dt=self.cfg.dt,
- rendering_dt=self.cfg.dt * self.cfg.render_interval,
- backend="torch",
- sim_params=sim_params,
- physics_prim_path=self.cfg.physics_prim_path,
- device=self.cfg.device,
- stage=self._initial_stage,
- )
- self.carb_settings.set_bool("/app/player/playSimulations", False)
+ # # create a simulation context to control the simulator
+ # if float(".".join(self._isaacsim_version[2])) < 5:
+ # # stage arg is not supported before isaac sim 5.0
+ # super().__init__(
+ # stage_units_in_meters=1.0,
+ # physics_dt=self.cfg.dt,
+ # rendering_dt=self.cfg.dt * self.cfg.render_interval,
+ # backend="torch",
+ # sim_params=sim_params,
+ # physics_prim_path=self.cfg.physics_prim_path,
+ # device=self.cfg.device,
+ # )
+ # else:
+ # super().__init__(
+ # stage_units_in_meters=1.0,
+ # physics_dt=self.cfg.dt,
+ # rendering_dt=self.cfg.dt * self.cfg.render_interval,
+ # backend="torch",
+ # sim_params=sim_params,
+ # physics_prim_path=self.cfg.physics_prim_path,
+ # device=self.cfg.device,
+ # stage=self._initial_stage,
+ # )
+
+ # initialize parameters here
+ self.physics_dt = self.cfg.dt
+ self.rendering_dt = self.cfg.dt * self.cfg.render_interval
+ self.backend = "torch"
+ self.physics_prim_path = self.cfg.physics_prim_path
+ self.device = self.cfg.device
+
+ self._is_playing = False
+ self.physics_sim_view = None
+
+ self.settings.set_bool("/app/player/playSimulations", False)
NewtonManager.set_simulation_dt(self.cfg.dt)
NewtonManager.set_solver_settings(newton_params)
- physx_sim_interface = omni.physx.get_physx_simulation_interface()
- physx_sim_interface.detach_stage()
- get_physics_stage_update_node_interface().detach_node()
+ try:
+ import omni.physx
+ from omni.physics.stageupdate import get_physics_stage_update_node_interface
+
+ physx_sim_interface = omni.physx.get_physx_simulation_interface()
+ physx_sim_interface.detach_stage()
+ get_physics_stage_update_node_interface().detach_node()
+ except Exception:
+ pass
# Disable USD cloning if we are not rendering or using RTX sensors
NewtonManager._clone_physics_only = (
self.render_mode == self.RenderMode.NO_GUI_OR_RENDERING or self.render_mode == self.RenderMode.NO_RENDERING
)
+ # Mark as initialized (singleton pattern)
+ self._initialized = True
+
def _apply_physics_settings(self):
"""Sets various carb physics settings."""
# enable hydra scene-graph instancing
# note: this allows rendering of instanceable assets on the GUI
- self.carb_settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True)
+ self.settings.set("/persistent/omnihydra/useSceneGraphInstancing", True)
def _apply_render_settings_from_cfg(self):
"""Sets rtx settings specified in the RenderCfg."""
@@ -340,6 +405,8 @@ def _apply_render_settings_from_cfg(self):
)
# parse preset file
+ import carb
+
repo_path = os.path.join(carb.tokens.get_tokens_interface().resolve("${app}"), "..")
preset_filename = os.path.join(repo_path, f"apps/rendering_modes/{rendering_mode}.kit")
with open(preset_filename) as file:
@@ -349,7 +416,7 @@ def _apply_render_settings_from_cfg(self):
# set presets
for key, value in preset_dict.items():
key = "/" + key.replace(".", "/") # convert to carb setting format
- self.set_setting(key, value)
+ self.settings.set(key, value)
# set user-friendly named settings
for key, value in vars(self.cfg.render_cfg).items():
@@ -362,7 +429,7 @@ def _apply_render_settings_from_cfg(self):
" need to be updated."
)
key = rendering_setting_name_mapping[key]
- self.set_setting(key, value)
+ self.settings.set(key, value)
# set general carb settings
carb_settings = self.cfg.render_cfg.carb_settings
@@ -372,9 +439,9 @@ def _apply_render_settings_from_cfg(self):
key = "/" + key.replace("_", "/") # convert from python variable style string
elif "." in key:
key = "/" + key.replace(".", "/") # convert from .kit file style string
- if self.get_setting(key) is None:
+ if self.settings.get(key) is None:
raise ValueError(f"'{key}' in RenderCfg.general_parameters does not map to a carb setting.")
- self.set_setting(key, value)
+ self.settings.set(key, value)
# set denoiser mode
if self.cfg.render_cfg.antialiasing_mode is not None:
@@ -386,8 +453,9 @@ def _apply_render_settings_from_cfg(self):
pass
# WAR: Ensure /rtx/renderMode RaytracedLighting is correctly cased.
- if self.get_setting("/rtx/rendermode").lower() == "raytracedlighting":
- self.set_setting("/rtx/rendermode", "RaytracedLighting")
+ render_mode = self.settings.get("/rtx/rendermode")
+ if render_mode is not None and render_mode.lower() == "raytracedlighting":
+ self.settings.set("/rtx/rendermode", "RaytracedLighting")
"""
Operations - New.
@@ -400,6 +468,35 @@ def has_gui(self) -> bool:
"""
return self._has_gui
+ def has_omniverse_visualizer(self) -> bool:
+ """Returns whether the Omniverse visualizer is enabled.
+
+ This checks both the configuration (before initialization) and the active visualizers
+ (after initialization) to determine if the Omniverse visualizer will be or is active.
+
+ Returns:
+ True if the Omniverse visualizer is requested or active, False otherwise.
+ """
+ # First, check if already initialized visualizers include OVVisualizer
+ for visualizer in self._visualizers:
+ # Check if visualizer has visualizer_type attribute set to "omniverse"
+ if hasattr(visualizer, "cfg") and hasattr(visualizer.cfg, "visualizer_type"):
+ if visualizer.cfg.visualizer_type == "omniverse":
+ return True
+ # Alternative: check the class name
+ if type(visualizer).__name__ == "OVVisualizer":
+ return True
+
+ # If not initialized yet, check the configuration/settings
+ requested_visualizers_str = self.settings.get("/isaaclab/visualizer")
+ if requested_visualizers_str:
+ requested_visualizers = [v.strip() for v in requested_visualizers_str.split(",") if v.strip()]
+ if "omniverse" in requested_visualizers:
+ # Only return True if we have a GUI (omniverse requires GUI)
+ return self._has_gui
+
+ return False
+
def has_rtx_sensors(self) -> bool:
"""Returns whether the simulation has any RTX-rendering related sensors.
@@ -413,7 +510,7 @@ def has_rtx_sensors(self) -> bool:
.. _NVIDIA RTX documentation: https://developer.nvidia.com/rendering-technologies
"""
- return self._settings.get_as_bool("/isaaclab/render/rtx_sensors")
+ return self.settings.get("/isaaclab/render/rtx_sensors")
def is_fabric_enabled(self) -> bool:
"""Returns whether the fabric interface is enabled.
@@ -428,18 +525,18 @@ def is_fabric_enabled(self) -> bool:
"""
return self._fabric_iface is not None
- def get_version(self) -> tuple[int, int, int]:
- """Returns the version of the simulator.
+ # def get_version(self) -> tuple[int, int, int]:
+ # """Returns the version of the simulator.
- This is a wrapper around the ``isaacsim.core.version.get_version()`` function.
+ # This is a wrapper around the ``isaacsim.core.version.get_version()`` function.
- The returned tuple contains the following information:
+ # The returned tuple contains the following information:
- * Major version (int): This is the year of the release (e.g. 2022).
- * Minor version (int): This is the half-year of the release (e.g. 1 or 2).
- * Patch version (int): This is the patch number of the release (e.g. 0).
- """
- return int(self._isaacsim_version[2]), int(self._isaacsim_version[3]), int(self._isaacsim_version[4])
+ # * Major version (int): This is the year of the release (e.g. 2022).
+ # * Minor version (int): This is the half-year of the release (e.g. 1 or 2).
+ # * Patch version (int): This is the patch number of the release (e.g. 0).
+ # """
+ # return int(self._isaacsim_version[2]), int(self._isaacsim_version[3]), int(self._isaacsim_version[4])
"""
Operations - New utilities.
@@ -453,19 +550,30 @@ def set_camera_view(
):
"""Set the location and target of the viewport camera in the stage.
- Note:
- This is a wrapper around the :math:`isaacsim.core.utils.viewports.set_camera_view` function.
- It is provided here for convenience to reduce the amount of imports needed.
+ This method sets the camera view by calling the OVVisualizer's set_camera_view method.
+ If no OVVisualizer is active, this method has no effect.
Args:
eye: The location of the camera eye.
target: The location of the camera target.
camera_prim_path: The path to the camera primitive in the stage. Defaults to
- "/OmniverseKit_Persp".
+ "/OmniverseKit_Persp". Note: This parameter is ignored as the camera path
+ is determined by the active viewport.
"""
- # safe call only if we have a GUI or viewport rendering enabled
- if self._has_gui or self._offscreen_render or self._render_viewport:
- set_camera_view(eye, target, camera_prim_path)
+ # Find the Omniverse visualizer and call its set_camera_view method
+ for visualizer in self._visualizers:
+ if hasattr(visualizer, "cfg") and hasattr(visualizer.cfg, "visualizer_type"):
+ if visualizer.cfg.visualizer_type == "omniverse":
+ if hasattr(visualizer, "set_camera_view"):
+ visualizer.set_camera_view(eye, target)
+ return
+ # Alternative: check the class name
+ if type(visualizer).__name__ == "OVVisualizer":
+ if hasattr(visualizer, "set_camera_view"):
+ visualizer.set_camera_view(eye, target)
+ return
+
+ logger.debug("No Omniverse visualizer found - set_camera_view has no effect.")
def set_render_mode(self, mode: RenderMode):
"""Change the current render mode of the simulation.
@@ -527,15 +635,15 @@ def set_setting(self, name: str, value: Any):
"""
# Route through typed setters for correctness and consistency for common scalar types.
if isinstance(value, bool):
- self.carb_settings.set_bool(name, value)
+ self.settings.set_bool(name, value)
elif isinstance(value, int):
- self.carb_settings.set_int(name, value)
+ self.settings.set_int(name, value)
elif isinstance(value, float):
- self.carb_settings.set_float(name, value)
+ self.settings.set_float(name, value)
elif isinstance(value, str):
- self.carb_settings.set_string(name, value)
+ self.settings.set_string(name, value)
elif isinstance(value, (list, tuple)):
- self.carb_settings.set(name, value)
+ self.settings.set(name, value)
else:
raise ValueError(f"Unsupported value type for setting '{name}': {type(value)}")
@@ -548,7 +656,7 @@ def get_setting(self, name: str) -> Any:
Returns:
The value of the setting.
"""
- return self.carb_settings.get(name)
+ return self.settings.get(name)
def forward(self) -> None:
"""Updates articulation kinematics and scene data for rendering."""
@@ -611,9 +719,9 @@ def initialize_visualizers(self) -> None:
- Only visualizers specified via --visualizer will be initialized, even if
multiple visualizer configs are present in the simulation config.
"""
+
# Check if specific visualizers were requested via command-line flag
- carb_settings_iface = carb.settings.get_settings()
- requested_visualizers_str = carb_settings_iface.get("/isaaclab/visualizer")
+ requested_visualizers_str = self.settings.get("/isaaclab/visualizer")
if requested_visualizers_str is None:
requested_visualizers_str = ""
@@ -796,20 +904,21 @@ def get_initial_stage(self) -> Usd.Stage:
"""
def reset(self, soft: bool = False):
- self.carb_settings.set_bool("/app/player/playSimulations", False)
+ self.settings.set_bool("/app/player/playSimulations", False)
self._disable_app_control_on_stop_handle = True
- # check if we need to raise an exception that was raised in a callback
- if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None:
- exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION
- builtins.ISAACLAB_CALLBACK_EXCEPTION = None
- raise exception_to_raise
+ # # check if we need to raise an exception that was raised in a callback
+ # if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None:
+ # exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION
+ # builtins.ISAACLAB_CALLBACK_EXCEPTION = None
+ # raise exception_to_raise
if not soft:
- if not self.is_stopped():
- self.stop()
+ # if not self.is_stopped():
+ # self.stop()
NewtonManager.start_simulation()
- self.play()
+ # self.play()
NewtonManager.initialize_solver()
+ self._is_playing = True
# app.update() may be changing the cuda device in reset, so we force it back to our desired device here
if "cuda" in self.device:
@@ -857,7 +966,9 @@ def step(self, render: bool = True):
# reason: physics has to parse the scene again and inform other extensions like hydra-delegate.
# without this the app becomes unresponsive.
# FIXME: This steps physics as well, which we is not good in general.
- self.app.update()
+ import omni.kit.app
+
+ omni.kit.app.get_app().update()
# step the simulation
if self.stage is None:
@@ -873,7 +984,9 @@ def step(self, render: bool = True):
elif self.get_rendering_dt() == 0 and self.get_physics_dt() != 0: # noqa: SIM114
SimulationContext.render(self)
else:
- self._app.update()
+ import omni.kit.app
+
+ omni.kit.app.get_app().update()
else:
if self.is_playing():
NewtonManager.step()
@@ -885,6 +998,14 @@ def step(self, render: bool = True):
if "cuda" in self.device:
torch.cuda.set_device(self.device)
+ def is_playing(self) -> bool:
+ """Checks if the simulation is playing.
+
+ Returns:
+ True if the simulation is playing, False otherwise.
+ """
+ return self._is_playing
+
def render(self, mode: RenderMode | None = None):
"""Refreshes the rendering components including UI elements and view-ports depending on the render mode.
@@ -897,6 +1018,8 @@ def render(self, mode: RenderMode | None = None):
Args:
mode: The rendering mode. Defaults to None, in which case the current rendering mode is used.
"""
+ import omni.kit.app
+
# check if we need to raise an exception that was raised in a callback
if builtins.ISAACLAB_CALLBACK_EXCEPTION is not None:
exception_to_raise = builtins.ISAACLAB_CALLBACK_EXCEPTION
@@ -916,16 +1039,16 @@ def render(self, mode: RenderMode | None = None):
self._render_throttle_counter = 0
# here we don't render viewport so don't need to flush fabric data
# note: we don't call super().render() anymore because they do flush the fabric data
- self.carb_settings.set_bool("/app/player/playSimulations", False)
- self._app.update()
+ self.settings.set_bool("/app/player/playSimulations", False)
+ omni.kit.app.get_app().update()
else:
# manually flush the fabric data to update Hydra textures
self.forward()
# render the simulation
# note: we don't call super().render() anymore because they do above operation inside
# and we don't want to do it twice. We may remove it once we drop support for Isaac Sim 2022.2.
- self.carb_settings.set_bool("/app/player/playSimulations", False)
- self._app.update()
+ self.settings.set_bool("/app/player/playSimulations", False)
+ omni.kit.app.get_app().update()
# app.update() may be changing the cuda device, so we force it back to our desired device here
if "cuda" in self.device:
@@ -938,6 +1061,8 @@ def render(self, mode: RenderMode | None = None):
async def reset_async(self, soft: bool = False):
# need to load all "physics" information from the USD file
if not soft:
+ import omni.physx
+
omni.physx.acquire_physx_interface().force_load_physics_from_usd()
# play the simulation
await super().reset_async(soft=soft)
@@ -951,9 +1076,9 @@ def _init_stage(self, *args, **kwargs) -> Usd.Stage:
with 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.carb_settings.set_bool("/app/player/playSimulations", False)
+ self.settings.set_bool("/app/player/playSimulations", False)
self._app.update()
- self.carb_settings.set_bool("/app/player/playSimulations", True)
+ self.settings.set_bool("/app/player/playSimulations", True)
# set additional physx parameters and bind material
self._set_additional_physics_params()
# load flatcache/fabric interface
@@ -972,16 +1097,31 @@ async def _initialize_stage_async(self, *args, **kwargs) -> Usd.Stage:
@classmethod
def clear_instance(cls):
+ """Clear the singleton instance and clean up resources.
+
+ This method should be called when you want to destroy the simulation context
+ and create a new one with different settings.
+ """
# clear the callback
if cls._instance is not None:
- if cls._instance._app_control_on_stop_handle is not None:
+ if (
+ hasattr(cls._instance, "_app_control_on_stop_handle")
+ and cls._instance._app_control_on_stop_handle is not None
+ ):
cls._instance._app_control_on_stop_handle.unsubscribe()
cls._instance._app_control_on_stop_handle = None
# close all visualizers
if hasattr(cls._instance, "_visualizers"):
cls._instance.close_visualizers()
- # call parent to clear the instance
- super().clear_instance()
+ # clear stage references
+ if hasattr(cls._instance, "_initial_stage"):
+ cls._instance._initial_stage = None
+ if hasattr(cls._instance, "stage"):
+ cls._instance.stage = None
+ # reset initialization flag
+ cls._instance._initialized = False
+ # clear the singleton instance
+ cls._instance = None
NewtonManager.clear()
"""
@@ -1027,27 +1167,27 @@ def _load_fabric_interface(self):
Callbacks.
"""
- def _app_control_on_stop_handle_fn(self, event: carb.events.IEvent):
- """Callback to deal with the app when the simulation is stopped.
-
- Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to
- resume the simulation from the last state. This leaves the app in an inconsistent state, where
- two possible actions can be taken:
-
- 1. **Keep the app rendering**: In this case, the simulation is kept running and the app is not shutdown.
- However, the physics is not updated and the script cannot be resumed from the last state. The
- user has to manually close the app to stop the simulation.
- 2. **Shutdown the app**: This is the default behavior. In this case, the app is shutdown and
- the simulation is stopped.
-
- Note:
- This callback is used only when running the simulation in a standalone python script. In an extension,
- it is expected that the user handles the extension shutdown.
- """
- if not self._disable_app_control_on_stop_handle:
- while not omni.timeline.get_timeline_interface().is_playing():
- self.render()
- return
+ # def _app_control_on_stop_handle_fn(self, event: carb.events.IEvent):
+ # """Callback to deal with the app when the simulation is stopped.
+
+ # Once the simulation is stopped, the physics handles go invalid. After that, it is not possible to
+ # resume the simulation from the last state. This leaves the app in an inconsistent state, where
+ # two possible actions can be taken:
+
+ # 1. **Keep the app rendering**: In this case, the simulation is kept running and the app is not shutdown.
+ # However, the physics is not updated and the script cannot be resumed from the last state. The
+ # user has to manually close the app to stop the simulation.
+ # 2. **Shutdown the app**: This is the default behavior. In this case, the app is shutdown and
+ # the simulation is stopped.
+
+ # Note:
+ # This callback is used only when running the simulation in a standalone python script. In an extension,
+ # it is expected that the user handles the extension shutdown.
+ # """
+ # if not self._disable_app_control_on_stop_handle:
+ # while not omni.timeline.get_timeline_interface().is_playing():
+ # self.render()
+ # return
@contextmanager
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 2a7cb14a0b2..d1c4b2cf576 100644
--- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py
+++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py
@@ -6,28 +6,18 @@
from __future__ import annotations
import logging
+import os
+import shutil
from typing import TYPE_CHECKING
+from urllib.parse import urljoin
-import omni.kit.commands
-from pxr import Gf, Sdf, Usd
+from pxr import Gf, Sdf, Usd, UsdGeom
import isaaclab.sim.utils.prims as prim_utils
-
-# from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated
-try:
- import Semantics
-except ModuleNotFoundError:
- from pxr import Semantics
-
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
+from isaaclab.utils.assets import check_file_path, retrieve_file_path
if TYPE_CHECKING:
from . import from_files_cfg
@@ -181,43 +171,46 @@ def spawn_ground_plane(
# Change the color of the plane
# Warning: This is specific to the default grid plane asset.
if cfg.color is not None:
- # avoiding this step if stage is in memory since the "ChangePropertyCommand" kit command
- # is not supported in stage in memory
- if is_current_stage_in_memory():
- logger.warning(
- "Ground plane color modification is not supported while the stage is in memory. Skipping operation."
- )
+ # change the color using USD core API
+ stage = get_current_stage()
+ shader_prim = stage.GetPrimAtPath(f"{prim_path}/Looks/theGrid/Shader")
+ if shader_prim.IsValid():
+ diffuse_attr = shader_prim.GetAttribute("inputs:diffuse_tint")
+ if not diffuse_attr:
+ diffuse_attr = shader_prim.CreateAttribute("inputs:diffuse_tint", Sdf.ValueTypeNames.Color3f)
+ diffuse_attr.Set(Gf.Vec3f(*cfg.color))
- else:
- prop_path = f"{prim_path}/Looks/theGrid/Shader.inputs:diffuse_tint"
-
- # change the color
- omni.kit.commands.execute(
- "ChangePropertyCommand",
- prop_path=Sdf.Path(prop_path),
- value=Gf.Vec3f(*cfg.color),
- prev=None,
- type_to_create_if_not_exist=Sdf.ValueTypeNames.Color3f,
- )
# Remove the light from the ground plane
# It isn't bright enough and messes up with the user's lighting settings
stage = get_current_stage()
- omni.kit.commands.execute("ToggleVisibilitySelectedPrims", selected_paths=[f"{prim_path}/SphereLight"], stage=stage)
+ light_prim = stage.GetPrimAtPath(f"{prim_path}/SphereLight")
+ if light_prim.IsValid():
+ imageable = UsdGeom.Imageable(light_prim)
+ imageable.MakeInvisible()
prim = prim_utils.get_prim_at_path(prim_path)
- # Apply semantic tags
+ # Apply semantic tags using USD core APIs
if hasattr(cfg, "semantic_tags") and cfg.semantic_tags is not None:
- # note: taken from replicator scripts.utils.utils.py
for semantic_type, semantic_value in cfg.semantic_tags:
# deal with spaces by replacing them with underscores
semantic_type_sanitized = semantic_type.replace(" ", "_")
semantic_value_sanitized = semantic_value.replace(" ", "_")
- # set the semantic API for the instance
+ # create custom attributes for semantic labeling using USD core API
instance_name = f"{semantic_type_sanitized}_{semantic_value_sanitized}"
- sem = Semantics.SemanticsAPI.Apply(prim, instance_name)
- # create semantic type and data attributes
- sem.CreateSemanticTypeAttr().Set(semantic_type)
- sem.CreateSemanticDataAttr().Set(semantic_value)
+
+ # Create semantic type attribute
+ type_attr_name = f"semantic:{instance_name}:semantic:type"
+ type_attr = prim.GetAttribute(type_attr_name)
+ if not type_attr:
+ type_attr = prim.CreateAttribute(type_attr_name, Sdf.ValueTypeNames.String)
+ type_attr.Set(semantic_type)
+
+ # Create semantic data attribute
+ data_attr_name = f"semantic:{instance_name}:semantic:data"
+ data_attr = prim.GetAttribute(data_attr_name)
+ if not data_attr:
+ data_attr = prim.CreateAttribute(data_attr_name, Sdf.ValueTypeNames.String)
+ data_attr.Set(semantic_value)
# return the prim
return prim
@@ -227,6 +220,64 @@ def spawn_ground_plane(
"""
+def _download_usd_with_dependencies(usd_url: str, base_download_dir: str | None = None) -> str:
+ """Download a USD file and attempt to download the entire directory.
+
+ Since USD files can have complex nested dependencies, we download the entire
+ directory structure where the USD file is located to ensure all references work.
+
+ Args:
+ usd_url: The URL to the USD file (HTTP, HTTPS, or S3).
+ base_download_dir: Optional base directory for downloads. If None, uses default cache.
+
+ Returns:
+ The local path to the downloaded USD file with all dependencies resolved.
+ """
+ # Download the main USD file
+ logger.info(f"Downloading USD file and dependencies from: {usd_url}")
+ local_usd_path = retrieve_file_path(usd_url, download_dir=base_download_dir, force_download=False)
+ logger.info(f" Main file downloaded to: {local_usd_path}")
+
+ # For S3 and web URLs, try to download common dependency files
+ # Assume the directory structure might contain Props, Materials, etc.
+ base_url = usd_url.rsplit("/", 1)[0] + "/"
+ local_base_dir = os.path.dirname(local_usd_path)
+
+ # Try to download common dependency folders that Isaac assets typically use
+ common_folders = ["Props", "Materials", "Textures"]
+
+ for folder in common_folders:
+ try:
+ # Try to download an index or common files from these folders
+ # We'll attempt to download instanceable_meshes.usd which is commonly referenced
+ common_files = [
+ f"{folder}/instanceable_meshes.usd",
+ f"{folder}/instanceable_meshes.usda",
+ ]
+
+ for common_file in common_files:
+ file_url = urljoin(base_url, common_file)
+ try:
+ logger.info(f" Attempting to download: {common_file}")
+ downloaded_path = retrieve_file_path(file_url, download_dir=base_download_dir, force_download=False)
+
+ # Copy to maintain directory structure
+ local_file_path = os.path.join(local_base_dir, common_file)
+ os.makedirs(os.path.dirname(local_file_path), exist_ok=True)
+
+ if downloaded_path != local_file_path:
+ shutil.copy2(downloaded_path, local_file_path)
+ logger.info(f" Copied to: {local_file_path}")
+ except Exception:
+ # File might not exist, that's okay
+ pass
+ except Exception:
+ # Folder might not exist, that's okay
+ pass
+
+ return local_usd_path
+
+
def _spawn_from_usd_file(
prim_path: str,
usd_path: str,
@@ -258,20 +309,16 @@ def _spawn_from_usd_file(
Raises:
FileNotFoundError: If the USD file does not exist at the given path.
"""
- # get stage handle
- stage = get_current_stage()
-
- # check file path exists
- if not stage.ResolveIdentifierToEditTarget(usd_path):
- if "4.5" in usd_path:
- usd_5_0_path = (
- usd_path.replace("http", "https").replace("-production.", "-staging.").replace("/4.5", "/5.0")
- )
- if not stage.ResolveIdentifierToEditTarget(usd_5_0_path):
- raise FileNotFoundError(f"USD file not found at path at either: '{usd_path}' or '{usd_5_0_path}'.")
- usd_path = usd_5_0_path
- else:
- raise FileNotFoundError(f"USD file not found at path at: '{usd_path}'.")
+ # check file path exists (supports local paths, S3, HTTP/HTTPS URLs)
+ # check_file_path returns: 0 (not found), 1 (local), 2 (remote)
+ file_status = check_file_path(usd_path)
+ if file_status == 0:
+ raise FileNotFoundError(f"USD file not found at path: '{usd_path}'.")
+
+ # Download remote files (S3, HTTP, HTTPS) to local cache
+ # This also downloads all USD dependencies to maintain references
+ if file_status == 2:
+ usd_path = retrieve_file_path(usd_path)
# spawn asset if it doesn't exist.
if not prim_utils.is_prim_path_valid(prim_path):
# add prim as reference to stage
diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py
index be62d2bf4e5..ea10957a5ab 100644
--- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py
+++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py
@@ -8,7 +8,6 @@
import logging
from typing import TYPE_CHECKING
-import omni.kit.commands
from pxr import Usd
import isaaclab.sim.utils.prims as prim_utils
@@ -55,6 +54,8 @@ def spawn_preview_surface(prim_path: str, cfg: visual_materials_cfg.PreviewSurfa
# since stage in memory is not supported by the "CreatePreviewSurfaceMaterialPrim" kit command
attach_stage_to_usd_context(attaching_early=True)
+ import omni.kit.commands
+
omni.kit.commands.execute("CreatePreviewSurfaceMaterialPrim", mtl_path=prim_path, select_new_prim=False)
else:
raise ValueError(f"A prim already exists at path: '{prim_path}'.")
@@ -107,6 +108,8 @@ def spawn_from_mdl_file(prim_path: str, cfg: visual_materials_cfg.MdlMaterialCfg
# extract material name from path
material_name = cfg.mdl_path.split("/")[-1].split(".")[0]
+ import omni.kit.commands
+
omni.kit.commands.execute(
"CreateMdlMaterialPrim",
mtl_url=cfg.mdl_path.format(NVIDIA_NUCLEUS_DIR=NVIDIA_NUCLEUS_DIR),
diff --git a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py
index 492ed5bddae..71cabbcae14 100644
--- a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py
+++ b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py
@@ -8,11 +8,10 @@
import logging
from typing import TYPE_CHECKING
-import omni.kit.commands
from pxr import Sdf, Usd
import isaaclab.sim.utils.prims as prim_utils
-from isaaclab.sim.utils import attach_stage_to_usd_context, clone
+from isaaclab.sim.utils import clone
from isaaclab.utils import to_camel_case
if TYPE_CHECKING:
@@ -91,17 +90,13 @@ def spawn_camera(
# lock camera from viewport (this disables viewport movement for camera)
if cfg.lock_camera:
- # 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)
-
- omni.kit.commands.execute(
- "ChangePropertyCommand",
- prop_path=Sdf.Path(f"{prim_path}.omni:kit:cameraLock"),
- value=True,
- prev=None,
- type_to_create_if_not_exist=Sdf.ValueTypeNames.Bool,
- )
+ # Set camera lock attribute using USD core API
+ prim = prim_utils.get_prim_at_path(prim_path)
+ if prim.IsValid():
+ lock_attr = prim.GetAttribute("omni:kit:cameraLock")
+ if not lock_attr:
+ lock_attr = prim.CreateAttribute("omni:kit:cameraLock", Sdf.ValueTypeNames.Bool)
+ lock_attr.Set(True)
# decide the custom attributes to add
if cfg.projection_type == "pinhole":
attribute_types = CUSTOM_PINHOLE_CAMERA_ATTRIBUTES
diff --git a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py
index a1cbc1f1c56..e2696da493f 100644
--- a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py
+++ b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py
@@ -5,22 +5,19 @@
from __future__ import annotations
-import random
-import re
+import logging
from typing import TYPE_CHECKING
-import carb
-from pxr import Sdf, Usd
+from pxr import Usd
-import isaaclab.sim as sim_utils
import isaaclab.sim.utils.prims as prim_utils
-import isaaclab.sim.utils.stage as stage_utils
from isaaclab.sim.spawners.from_files import UsdFileCfg
-from isaaclab.sim.utils.stage import get_current_stage
if TYPE_CHECKING:
from . import wrappers_cfg
+logger = logging.getLogger(__name__)
+
def spawn_multi_asset(
prim_path: str,
@@ -30,11 +27,14 @@ def spawn_multi_asset(
clone_in_fabric: bool = False,
replicate_physics: bool = False,
) -> Usd.Prim:
- """Spawn multiple assets based on the provided configurations.
+ """Spawn multiple assets into numbered prim paths derived from the provided configuration.
- This function spawns multiple assets based on the provided configurations. The assets are spawned
- in the order they are provided in the list. If the :attr:`~MultiAssetSpawnerCfg.random_choice` parameter is
- set to True, a random asset configuration is selected for each spawn.
+ Assets are created in the order they appear in ``cfg.assets_cfg`` using the base name in ``prim_path``,
+ which must contain ``.*`` (for example, ``/World/Env_0/asset_.*`` spawns ``asset_0``, ``asset_1``, ...).
+ The prefix portion of ``prim_path`` may also include ``.*`` (for example, ``/World/env_.*/asset_.*``);
+ this is only allowed when :attr:`~isaaclab.sim.spawners.wrappers.wrappers_cfg.MultiAssetSpawnerCfg.enable_clone`
+ is True, in which case assets are spawned under the first match (``env_0``) and that structure is cloned to
+ other matching environments.
Args:
prim_path: The prim path to spawn the assets.
@@ -47,32 +47,27 @@ def spawn_multi_asset(
Returns:
The created prim at the first prim path.
"""
- # get stage handle
- stage = get_current_stage()
-
- # resolve: {SPAWN_NS}/AssetName
- # note: this assumes that the spawn namespace already exists in the stage
- root_path, asset_path = prim_path.rsplit("/", 1)
- # check if input is a regex expression
- # note: a valid prim path can only contain alphanumeric characters, underscores, and forward slashes
- is_regex_expression = re.match(r"^[a-zA-Z0-9/_]+$", root_path) is None
-
- # resolve matching prims for source prim path expression
- if is_regex_expression and root_path != "":
- source_prim_paths = sim_utils.find_matching_prim_paths(root_path)
- # if no matching prims are found, raise an error
- if len(source_prim_paths) == 0:
- raise RuntimeError(
- f"Unable to find source prim path: '{root_path}'. Please create the prim before spawning."
- )
- else:
- source_prim_paths = [root_path]
-
- # find a free prim path to hold all the template prims
- template_prim_path = stage_utils.get_next_free_path("/World/Template")
- prim_utils.create_prim(template_prim_path, "Scope")
+ split_path = prim_path.split("/")
+ prefix_path, base_name = "/".join(split_path[:-1]), split_path[-1]
+ if ".*" in prefix_path and not cfg.enable_clone:
+ raise ValueError(
+ f" Found '.*' in prefix path '{prefix_path}' but enable_clone is False. Set enable_clone=True to allow"
+ f" this pattern, which would replicate all {len(cfg.assets_cfg)} assets into every environment that"
+ " matches the prefix. If you want heterogeneous assets across envs, instead of set enable_clone to True"
+ "spawn them under a single template (e.g., /World/Template/Robot) and use the cloner to place"
+ "them at their final paths."
+ )
+ if ".*" not in base_name:
+ raise ValueError(
+ f" The base name '{base_name}' in the prim path '{prim_path}' must contain '.*' to indicate"
+ " the path each individual multiple-asset to be spawned."
+ )
+ if cfg.random_choice:
+ logger.warning(
+ "`random_choice` parameter in `spawn_multi_asset` is deprecated, and nothing will happen. "
+ "Use `isaaclab.scene.interactive_scene_cfg.InteractiveSceneCfg.random_heterogeneous_cloning` instead."
+ )
- # spawn everything first in a "Dataset" prim
proto_prim_paths = list()
for index, asset_cfg in enumerate(cfg.assets_cfg):
# append semantic tags if specified
@@ -87,8 +82,8 @@ def spawn_multi_asset(
attr_value = getattr(cfg, attr_name)
if hasattr(asset_cfg, attr_name) and attr_value is not None:
setattr(asset_cfg, attr_name, attr_value)
- # spawn single instance
- proto_prim_path = f"{template_prim_path}/Asset_{index:04d}"
+
+ proto_prim_path = f"{prefix_path}/{base_name.replace('.*', str(index))}"
asset_cfg.func(
proto_prim_path,
asset_cfg,
@@ -100,35 +95,7 @@ def spawn_multi_asset(
# append to proto prim paths
proto_prim_paths.append(proto_prim_path)
- # resolve prim paths for spawning and cloning
- prim_paths = [f"{source_prim_path}/{asset_path}" for source_prim_path in source_prim_paths]
-
- # manually clone prims if the source prim path is a regex expression
- # note: unlike in the cloner API from Isaac Sim, we do not "reset" xforms on the copied prims.
- # This is because the "spawn" calls during the creation of the proto prims already handles this operation.
- with Sdf.ChangeBlock():
- for index, prim_path in enumerate(prim_paths):
- # spawn single instance
- env_spec = Sdf.CreatePrimInLayer(stage.GetRootLayer(), prim_path)
- # randomly select an asset configuration
- if cfg.random_choice:
- proto_path = random.choice(proto_prim_paths)
- else:
- proto_path = proto_prim_paths[index % len(proto_prim_paths)]
- # copy the proto prim
- Sdf.CopySpec(env_spec.layer, Sdf.Path(proto_path), env_spec.layer, Sdf.Path(prim_path))
-
- # delete the dataset prim after spawning
- prim_utils.delete_prim(template_prim_path)
-
- # set carb setting to indicate Isaac Lab's environments that different prims have been spawned
- # at varying prim paths. In this case, PhysX parser shouldn't optimize the stage parsing.
- # the flag is mainly used to inform the user that they should disable `InteractiveScene.replicate_physics`
- carb_settings_iface = carb.settings.get_settings()
- carb_settings_iface.set_bool("/isaaclab/spawn/multi_assets", True)
-
- # return the prim
- return prim_utils.get_prim_at_path(prim_paths[0])
+ return prim_utils.find_first_matching_prim(proto_prim_paths[0])
def spawn_multi_usd_file(
@@ -178,8 +145,6 @@ def spawn_multi_usd_file(
for usd_path in usd_paths:
usd_cfg = usd_template_cfg.replace(usd_path=usd_path)
multi_asset_cfg.assets_cfg.append(usd_cfg)
- # set random choice
- multi_asset_cfg.random_choice = cfg.random_choice
# propagate the contact sensor settings
# note: the default value for activate_contact_sensors in MultiAssetSpawnerCfg is False.
diff --git a/source/isaaclab/isaaclab/sim/utils/__init__.py b/source/isaaclab/isaaclab/sim/utils/__init__.py
index a03ed9180ec..3176e1e61a9 100644
--- a/source/isaaclab/isaaclab/sim/utils/__init__.py
+++ b/source/isaaclab/isaaclab/sim/utils/__init__.py
@@ -4,7 +4,5 @@
# SPDX-License-Identifier: BSD-3-Clause
from .logger import * # noqa: F401, F403
-from .nucleus import * # noqa: F401, F403
from .prims import * # noqa: F401, F403
-from .semantics import * # noqa: F401, F403
from .stage import * # noqa: F401, F403
diff --git a/source/isaaclab/isaaclab/sim/utils/nucleus.py b/source/isaaclab/isaaclab/sim/utils/nucleus.py
deleted file mode 100644
index cb7af95e555..00000000000
--- a/source/isaaclab/isaaclab/sim/utils/nucleus.py
+++ /dev/null
@@ -1,76 +0,0 @@
-# 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 logging
-
-import carb
-import omni.client
-from omni.client import Result
-
-logger = logging.getLogger(__name__)
-
-DEFAULT_ASSET_ROOT_PATH_SETTING = "/persistent/isaac/asset_root/default"
-DEFAULT_ASSET_ROOT_TIMEOUT_SETTING = "/persistent/isaac/asset_root/timeout"
-
-
-def check_server(server: str, path: str, timeout: float = 10.0) -> bool:
- """Check a specific server for a path
-
- Args:
- server (str): Name of Nucleus server
- path (str): Path to search
- timeout (float): Default value: 10 seconds
-
- Returns:
- bool: True if folder is found
- """
- logger.info(f"Checking path: {server}{path}")
- # Increase hang detection timeout
- omni.client.set_hang_detection_time_ms(20000)
- result, _ = omni.client.stat(f"{server}{path}")
- if result == Result.OK:
- logger.info(f"Success: {server}{path}")
- return True
- else:
- logger.info(f"Failure: {server}{path} not accessible")
- return False
-
-
-def get_assets_root_path(*, skip_check: bool = False) -> str:
- """Tries to find the root path to the Isaac Sim assets on a Nucleus server
-
- Args:
- skip_check (bool): If True, skip the checking step to verify that the resolved path exists.
-
- Raises:
- RuntimeError: if the root path setting is not set.
- RuntimeError: if the root path is not found.
-
- Returns:
- url (str): URL of Nucleus server with root path to assets folder.
- """
-
- # get timeout
- timeout = carb.settings.get_settings().get(DEFAULT_ASSET_ROOT_TIMEOUT_SETTING)
- if not isinstance(timeout, (int, float)):
- timeout = 10.0
-
- # resolve path
- logger.info(f"Check {DEFAULT_ASSET_ROOT_PATH_SETTING} setting")
- default_asset_root = carb.settings.get_settings().get(DEFAULT_ASSET_ROOT_PATH_SETTING)
- if not default_asset_root:
- raise RuntimeError(f"The '{DEFAULT_ASSET_ROOT_PATH_SETTING}' setting is not set")
- if skip_check:
- return default_asset_root
-
- # check path
- result = check_server(default_asset_root, "/Isaac", timeout)
- if result:
- result = check_server(default_asset_root, "/NVIDIA", timeout)
- if result:
- logger.info(f"Assets root found at {default_asset_root}")
- return default_asset_root
-
- raise RuntimeError(f"Could not find assets root folder: {default_asset_root}")
diff --git a/source/isaaclab/isaaclab/sim/utils/prims.py b/source/isaaclab/isaaclab/sim/utils/prims.py
index ba3089adb3b..c157eecfcd0 100644
--- a/source/isaaclab/isaaclab/sim/utils/prims.py
+++ b/source/isaaclab/isaaclab/sim/utils/prims.py
@@ -10,32 +10,19 @@
import logging
import numpy as np
import re
+import torch
from collections.abc import Callable, Sequence
from typing import TYPE_CHECKING, Any
-import omni
-import omni.kit.commands
-import omni.usd
-import usdrt
-from isaacsim.core.cloner import Cloner
-from isaacsim.core.version import get_version
-from omni.usd.commands import DeletePrimsCommand, MovePrimCommand
-from pxr import Sdf, Usd, UsdGeom, UsdPhysics, UsdShade
+from pxr import Gf, Sdf, Usd, UsdGeom, UsdPhysics, UsdShade
+from isaaclab.sim.prims import XFormPrim
+from isaaclab.sim.utils.stage import add_reference_to_stage, get_current_stage
from isaaclab.utils.string import to_camel_case
-from .semantics import add_labels
-from .stage import add_reference_to_stage, get_current_stage
-
if TYPE_CHECKING:
from isaaclab.sim.spawners.spawner_cfg import SpawnerCfg
-# from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated
-try:
- import Semantics
-except ModuleNotFoundError:
- from pxr import Semantics
-
# import logger
logger = logging.getLogger(__name__)
@@ -135,9 +122,6 @@ def create_prim(
... )
Usd.Prim()
"""
- # Note: Imported here to prevent cyclic dependency in the module.
- from isaacsim.core.prims import XFormPrim
-
# create prim in stage
prim = define_prim(prim_path=prim_path, prim_type=prim_type)
if not prim:
@@ -149,29 +133,31 @@ def create_prim(
# add reference to USD file
if usd_path is not None:
add_reference_to_stage(usd_path=usd_path, prim_path=prim_path)
- # add semantic label to prim
+ # add semantic label to prim using USD core API
if semantic_label is not None:
- add_labels(prim, labels=[semantic_label], instance_name=semantic_type)
- # apply the transformations
- from isaacsim.core.api.simulation_context.simulation_context import SimulationContext
-
- if SimulationContext.instance() is None:
- # FIXME: remove this, we should never even use backend utils especially not numpy ones
- import isaacsim.core.utils.numpy as backend_utils
-
- device = "cpu"
- else:
- backend_utils = SimulationContext.instance().backend_utils
- device = SimulationContext.instance().device
- if position is not None:
- position = backend_utils.expand_dims(backend_utils.convert(position, device), 0)
- if translation is not None:
- translation = backend_utils.expand_dims(backend_utils.convert(translation, device), 0)
- if orientation is not None:
- orientation = backend_utils.expand_dims(backend_utils.convert(orientation, device), 0)
- if scale is not None:
- scale = backend_utils.expand_dims(backend_utils.convert(scale, device), 0)
- XFormPrim(prim_path, positions=position, translations=translation, orientations=orientation, scales=scale)
+ # Create custom attributes for semantic labeling
+ semantic_type_sanitized = semantic_type.replace(" ", "_")
+ semantic_label_sanitized = semantic_label.replace(" ", "_")
+ instance_name = f"{semantic_type_sanitized}_{semantic_label_sanitized}"
+
+ # Create semantic type attribute
+ type_attr_name = f"semantic:{instance_name}:semantic:type"
+ type_attr = prim.GetAttribute(type_attr_name)
+ if not type_attr:
+ type_attr = prim.CreateAttribute(type_attr_name, Sdf.ValueTypeNames.String)
+ type_attr.Set(semantic_type)
+
+ # Create semantic data attribute (using label as data)
+ data_attr_name = f"semantic:{instance_name}:semantic:data"
+ data_attr = prim.GetAttribute(data_attr_name)
+ if not data_attr:
+ data_attr = prim.CreateAttribute(data_attr_name, Sdf.ValueTypeNames.String)
+ data_attr.Set(semantic_label)
+
+ # Apply the transformations using pure USD implementation
+ # XFormPrim handles conversion of position/translation/orientation/scale automatically
+ if position is not None or translation is not None or orientation is not None or scale is not None:
+ XFormPrim(prim_path, positions=position, translations=translation, orientations=orientation, scales=scale)
return prim
@@ -190,10 +176,12 @@ def delete_prim(prim_path: str) -> None:
>>>
>>> prims_utils.delete_prim("/World/Cube")
"""
+ from omni.usd.commands import DeletePrimsCommand
+
DeletePrimsCommand([prim_path]).do()
-def get_prim_at_path(prim_path: str, fabric: bool = False) -> Usd.Prim | usdrt.Usd._Usd.Prim:
+def get_prim_at_path(prim_path: str, fabric: bool = False) -> Usd.Prim:
"""Get the USD or Fabric Prim at a given path string
Args:
@@ -389,6 +377,8 @@ def move_prim(path_from: str, path_to: str) -> None:
>>> # given the stage: /World/Cube. Move the prim Cube outside the prim World
>>> prims_utils.move_prim("/World/Cube", "/Cube")
"""
+ from omni.usd.commands import MovePrimCommand
+
MovePrimCommand(path_from=path_from, path_to=path_to).do()
@@ -786,6 +776,8 @@ def is_prim_ancestral(prim_path: str) -> bool:
>>> prims_utils.is_prim_ancestral("/World/panda/panda_link0")
True
"""
+ import omni.usd
+
return omni.usd.check_ancestral(get_prim_at_path(prim_path))
@@ -1346,6 +1338,8 @@ def export_prim_to_file(
# set the default prim
target_layer.defaultPrim = Sdf.Path(target_prim_path).name
# resolve all paths relative to layer path
+ import omni.usd
+
omni.usd.resolve_paths(source_layer.identifier, target_layer.identifier)
# save the stage
target_layer.Save()
@@ -1481,10 +1475,10 @@ def wrapper(prim_path: str | Sdf.Path, cfg: SpawnerCfg, *args, **kwargs):
else:
source_prim_paths = [root_path]
- # resolve prim paths for spawning and cloning
- prim_paths = [f"{source_prim_path}/{asset_path}" for source_prim_path in source_prim_paths]
+ # resolve prim paths for spawning
+ prim_spawn_path = prim_path.replace(".*", "0")
# spawn single instance
- prim = func(prim_paths[0], cfg, *args, **kwargs)
+ prim = func(prim_spawn_path, cfg, *args, **kwargs)
# set the prim visibility
if hasattr(cfg, "visible"):
imageable = UsdGeom.Imageable(prim)
@@ -1494,45 +1488,43 @@ def wrapper(prim_path: str | Sdf.Path, cfg: SpawnerCfg, *args, **kwargs):
imageable.MakeInvisible()
# set the semantic annotations
if hasattr(cfg, "semantic_tags") and cfg.semantic_tags is not None:
- # note: taken from replicator scripts.utils.utils.py
for semantic_type, semantic_value in cfg.semantic_tags:
# deal with spaces by replacing them with underscores
semantic_type_sanitized = semantic_type.replace(" ", "_")
semantic_value_sanitized = semantic_value.replace(" ", "_")
- # set the semantic API for the instance
+ # create custom attributes for semantic labeling using USD core API
instance_name = f"{semantic_type_sanitized}_{semantic_value_sanitized}"
- sem = Semantics.SemanticsAPI.Apply(prim, instance_name)
- # create semantic type and data attributes
- sem.CreateSemanticTypeAttr()
- sem.CreateSemanticDataAttr()
- sem.GetSemanticTypeAttr().Set(semantic_type)
- sem.GetSemanticDataAttr().Set(semantic_value)
+
+ # Create semantic type attribute
+ type_attr_name = f"semantic:{instance_name}:semantic:type"
+ type_attr = prim.GetAttribute(type_attr_name)
+ if not type_attr:
+ type_attr = prim.CreateAttribute(type_attr_name, Sdf.ValueTypeNames.String)
+ type_attr.Set(semantic_type)
+
+ # Create semantic data attribute
+ data_attr_name = f"semantic:{instance_name}:semantic:data"
+ data_attr = prim.GetAttribute(data_attr_name)
+ if not data_attr:
+ data_attr = prim.CreateAttribute(data_attr_name, Sdf.ValueTypeNames.String)
+ data_attr.Set(semantic_value)
# activate rigid body contact sensors (lazy import to avoid circular import with schemas)
if hasattr(cfg, "activate_contact_sensors") and cfg.activate_contact_sensors:
from ..schemas import schemas as _schemas
- _schemas.activate_contact_sensors(prim_paths[0])
+ _schemas.activate_contact_sensors(prim_spawn_path)
# clone asset using cloner API
- if len(prim_paths) > 1:
- cloner = Cloner(stage=stage)
- # check version of Isaac Sim to determine whether clone_in_fabric is valid
- isaac_sim_version = float(".".join(get_version()[2]))
- if isaac_sim_version < 5:
- # clone the prim
- cloner.clone(
- prim_paths[0], prim_paths[1:], replicate_physics=False, copy_from_source=cfg.copy_from_source
- )
- else:
- # clone the prim
- clone_in_fabric = kwargs.get("clone_in_fabric", False)
- replicate_physics = kwargs.get("replicate_physics", False)
- cloner.clone(
- prim_paths[0],
- prim_paths[1:],
- replicate_physics=replicate_physics,
- copy_from_source=cfg.copy_from_source,
- clone_in_fabric=clone_in_fabric,
- )
+ if len(source_prim_paths) > 1:
+ # lazy import to avoid circular import
+ from isaaclab.cloner import usd_replicate
+
+ formattable_path = f"{root_path.replace('.*', '{}')}/{asset_path}"
+ usd_replicate(
+ stage=stage,
+ sources=[formattable_path.format(0)],
+ destinations=[formattable_path],
+ env_ids=torch.arange(len(source_prim_paths)),
+ )
# return the source prim
return prim
@@ -1589,6 +1581,8 @@ def bind_visual_material(
binding_strength = "weakerThanDescendants"
# obtain material binding API
# note: we prefer using the command here as it is more robust than the USD API
+ import omni.kit.commands
+
success, _ = omni.kit.commands.execute(
"BindMaterialCommand",
prim_path=prim_path,
@@ -1751,3 +1745,153 @@ class TableVariants:
f"Setting variant selection '{variant_selection}' for variant set '{variant_set_name}' on"
f" prim '{prim_path}'."
)
+
+
+def create_default_xform_ops(
+ prim_path: str | Sdf.Path,
+ stage: Usd.Stage | None = None,
+ xform_op_type: str = "Scale, Orient, Translate",
+ precision: str = "Double",
+) -> bool:
+ """Create default xform operations on a prim using USD core API.
+
+ This is a replacement for the omni.kit.commands "CreateDefaultXformOnPrimCommand" that uses
+ standard USD APIs instead of Omniverse-specific commands.
+
+ Args:
+ prim_path: The path to the prim to add xform ops to.
+ stage: The USD stage. If None, will get the current stage.
+ xform_op_type: The type of xform operations to create. Options are:
+ - "Scale, Rotate, Translate" - Creates translate, rotateXYZ, and scale ops
+ - "Scale, Orient, Translate" - Creates translate, orient (quat), and scale ops (default)
+ - "Transform" - Creates a single transform matrix op
+ precision: The precision for the xform ops. Options are "Double" or "Float". Defaults to "Double".
+
+ Returns:
+ True if successful, False if the prim is not xformable or doesn't exist.
+ """
+ if stage is None:
+ stage = get_current_stage()
+
+ if isinstance(prim_path, Sdf.Path):
+ prim_path = prim_path.pathString
+
+ prim = stage.GetPrimAtPath(prim_path)
+ if not prim or not prim.IsA(UsdGeom.Xformable):
+ logger.warning(f"Prim at path '{prim_path}' does not exist or is not Xformable.")
+ return False
+
+ with Sdf.ChangeBlock():
+ # Determine types based on precision
+ vec3_type = Sdf.ValueTypeNames.Double3 if precision == "Double" else Sdf.ValueTypeNames.Float3
+ quat_type = Sdf.ValueTypeNames.Quatd if precision == "Double" else Sdf.ValueTypeNames.Quatf
+ mat4_type = Sdf.ValueTypeNames.Matrix4d # Only Matrix4d exists in Sdf.ValueTypeNames
+
+ # Default values
+ if precision == "Double":
+ default_translate = Gf.Vec3d(0.0, 0.0, 0.0)
+ default_scale = Gf.Vec3d(1.0, 1.0, 1.0)
+ default_euler = Gf.Vec3d(0.0, 0.0, 0.0)
+ else:
+ default_translate = Gf.Vec3f(0.0, 0.0, 0.0)
+ default_scale = Gf.Vec3f(1.0, 1.0, 1.0)
+ default_euler = Gf.Vec3f(0.0, 0.0, 0.0)
+
+ # Create default orientation quaternion
+ rotation = (
+ Gf.Rotation(Gf.Vec3d.XAxis(), default_euler[0])
+ * Gf.Rotation(Gf.Vec3d.YAxis(), default_euler[1])
+ * Gf.Rotation(Gf.Vec3d.ZAxis(), default_euler[2])
+ )
+ quat = rotation.GetQuat()
+ default_orient = Gf.Quatd(quat) if precision == "Double" else Gf.Quatf(quat)
+
+ if xform_op_type == "Scale, Rotate, Translate":
+ # Create translate op
+ attr_translate = prim.GetAttribute("xformOp:translate")
+ if not attr_translate:
+ attr_translate = prim.CreateAttribute("xformOp:translate", vec3_type, False)
+ attr_translate.Set(default_translate)
+ elif attr_translate.GetTypeName() != vec3_type:
+ attr_translate.SetTypeName(vec3_type)
+
+ # Create rotate op (using XYZ rotation order)
+ attr_rotate = prim.GetAttribute("xformOp:rotateXYZ")
+ if not attr_rotate:
+ attr_rotate = prim.CreateAttribute("xformOp:rotateXYZ", vec3_type, False)
+ attr_rotate.Set(default_euler)
+ elif attr_rotate.GetTypeName() != vec3_type:
+ attr_rotate.SetTypeName(vec3_type)
+
+ # Create scale op
+ attr_scale = prim.GetAttribute("xformOp:scale")
+ if not attr_scale:
+ attr_scale = prim.CreateAttribute("xformOp:scale", vec3_type, False)
+ attr_scale.Set(default_scale)
+ elif attr_scale.GetTypeName() != vec3_type:
+ attr_scale.SetTypeName(vec3_type)
+
+ # Set xform op order
+ attr_order = prim.GetAttribute("xformOpOrder")
+ if not attr_order:
+ attr_order = prim.CreateAttribute("xformOpOrder", Sdf.ValueTypeNames.TokenArray, False)
+ attr_order.Set(["xformOp:translate", "xformOp:rotateXYZ", "xformOp:scale"])
+
+ elif xform_op_type == "Scale, Orient, Translate":
+ # Create translate op
+ attr_translate = prim.GetAttribute("xformOp:translate")
+ if not attr_translate:
+ attr_translate = prim.CreateAttribute("xformOp:translate", vec3_type, False)
+ attr_translate.Set(default_translate)
+ elif attr_translate.GetTypeName() != vec3_type:
+ attr_translate.SetTypeName(vec3_type)
+
+ # Create orient op
+ attr_orient = prim.GetAttribute("xformOp:orient")
+ if not attr_orient:
+ attr_orient = prim.CreateAttribute("xformOp:orient", quat_type, False)
+ attr_orient.Set(default_orient)
+ elif attr_orient.GetTypeName() != quat_type:
+ attr_orient.SetTypeName(quat_type)
+
+ # Create scale op
+ attr_scale = prim.GetAttribute("xformOp:scale")
+ if not attr_scale:
+ attr_scale = prim.CreateAttribute("xformOp:scale", vec3_type, False)
+ attr_scale.Set(default_scale)
+ elif attr_scale.GetTypeName() != vec3_type:
+ attr_scale.SetTypeName(vec3_type)
+
+ # Set xform op order
+ attr_order = prim.GetAttribute("xformOpOrder")
+ if not attr_order:
+ attr_order = prim.CreateAttribute("xformOpOrder", Sdf.ValueTypeNames.TokenArray, False)
+ attr_order.Set(["xformOp:translate", "xformOp:orient", "xformOp:scale"])
+
+ elif xform_op_type == "Transform":
+ # Create transform matrix op
+ attr_matrix = prim.GetAttribute("xformOp:transform")
+ if not attr_matrix:
+ attr_matrix = prim.CreateAttribute("xformOp:transform", mat4_type, False)
+ # Create identity transform matrix
+ transform_matrix = (
+ Gf.Matrix4d().SetScale(Gf.Vec3d(default_scale))
+ * Gf.Matrix4d().SetRotate(rotation)
+ * Gf.Matrix4d().SetTranslate(Gf.Vec3d(default_translate))
+ )
+ attr_matrix.Set(transform_matrix)
+
+ # Set xform op order
+ attr_order = prim.GetAttribute("xformOpOrder")
+ if not attr_order:
+ attr_order = prim.CreateAttribute("xformOpOrder", Sdf.ValueTypeNames.TokenArray, False)
+ attr_order.Set(["xformOp:transform"])
+
+ else:
+ logger.error(
+ f"Unknown xform_op_type: '{xform_op_type}'. Must be one of: "
+ "'Scale, Rotate, Translate', 'Scale, Orient, Translate', or 'Transform'"
+ )
+ return False
+
+ return True
diff --git a/source/isaaclab/isaaclab/sim/utils/semantics.py b/source/isaaclab/isaaclab/sim/utils/semantics.py
deleted file mode 100644
index ce629733f72..00000000000
--- a/source/isaaclab/isaaclab/sim/utils/semantics.py
+++ /dev/null
@@ -1,280 +0,0 @@
-# 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 logging
-
-from pxr import Usd, UsdGeom
-
-from isaaclab.sim.utils.stage import get_current_stage
-
-# from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated
-try:
- import Semantics
-except ModuleNotFoundError:
- from pxr import Semantics
-
-# import logger
-logger = logging.getLogger(__name__)
-
-
-def add_labels(prim: Usd.Prim, labels: list[str], instance_name: str = "class", overwrite: bool = True) -> None:
- """Apply semantic labels to a prim using the Semantics.LabelsAPI.
-
- Args:
- prim (Usd.Prim): Usd Prim to add or update labels on.
- labels (list): The list of labels to apply.
- instance_name (str, optional): The name of the semantic instance. Defaults to "class".
- overwrite (bool, optional): If True (default), existing labels for this instance are replaced.
- If False, the new labels are appended to existing ones (if any).
- """
- import omni.replicator.core.functional as F
-
- mode = "replace" if overwrite else "add"
- F.modify.semantics(prim, {instance_name: labels}, mode=mode)
-
-
-def get_labels(prim: Usd.Prim) -> dict[str, list[str]]:
- """Returns semantic labels (Semantics.LabelsAPI) applied to a prim.
-
- Args:
- prim (Usd.Prim): Prim to return labels for.
-
- Returns:
- dict[str, list[str]]: Dictionary mapping instance names to a list of labels.
- Returns an empty dict if no LabelsAPI instances are found.
- """
- result = {}
- for schema_name in prim.GetAppliedSchemas():
- if schema_name.startswith("SemanticsLabelsAPI:"):
- instance_name = schema_name.split(":", 1)[1]
- sem_api = Semantics.LabelsAPI(prim, instance_name)
- labels_attr = sem_api.GetLabelsAttr()
- if labels_attr:
- labels = labels_attr.Get()
- result[instance_name] = list(labels) if labels is not None else []
- else:
- result[instance_name] = []
- return result
-
-
-def remove_labels(prim: Usd.Prim, instance_name: str | None = None, include_descendants: bool = False) -> None:
- """Removes semantic labels (Semantics.LabelsAPI) from a prim.
-
- Args:
- prim (Usd.Prim): Prim to remove labels from.
- instance_name (str | None, optional): Specific instance name to remove.
- If None (default), removes *all* LabelsAPI instances.
- include_descendants (bool, optional): Also traverse children and remove labels recursively. Defaults to False.
- """
-
- def remove_single_prim_labels(target_prim: Usd.Prim):
- schemas_to_remove = []
- for schema_name in target_prim.GetAppliedSchemas():
- if schema_name.startswith("SemanticsLabelsAPI:"):
- current_instance = schema_name.split(":", 1)[1]
- if instance_name is None or current_instance == instance_name:
- schemas_to_remove.append(current_instance)
-
- for inst_to_remove in schemas_to_remove:
- target_prim.RemoveAPI(Semantics.LabelsAPI, inst_to_remove)
-
- if include_descendants:
- for p in Usd.PrimRange(prim):
- remove_single_prim_labels(p)
- else:
- remove_single_prim_labels(prim)
-
-
-def check_missing_labels(prim_path: str | None = None) -> list[str]:
- """Returns a list of prim paths of meshes with missing semantic labels (Semantics.LabelsAPI).
-
- Args:
- prim_path (str | None): This will check Prim path and its childrens' labels. If None, checks the whole stage.
-
- Returns:
- list[str]: Prim paths of meshes with no LabelsAPI applied.
- """
- prim_paths = []
- stage = get_current_stage()
- if stage is None:
- logger.warning("Invalid stage, skipping label check")
- return prim_paths
-
- start_prim = stage.GetPrimAtPath(prim_path) if prim_path else stage.GetPseudoRoot()
- if not start_prim:
- # Allow None prim_path for whole stage check, warn if path specified but not found
- if prim_path:
- logger.warning(f"Prim path not found: {prim_path}")
- return prim_paths
-
- prims_to_check = Usd.PrimRange(start_prim)
-
- for prim in prims_to_check:
- if prim.IsA(UsdGeom.Mesh):
- has_any_label = False
- for schema_name in prim.GetAppliedSchemas():
- if schema_name.startswith("SemanticsLabelsAPI:"):
- has_any_label = True
- break
- if not has_any_label:
- prim_paths.append(prim.GetPath().pathString)
- return prim_paths
-
-
-def check_incorrect_labels(prim_path: str | None = None) -> list[list[str]]:
- """Returns a list of [prim_path, label] for meshes where at least one semantic label (LabelsAPI)
- is not found within the prim's path string (case-insensitive, ignoring '_' and '-').
-
- Args:
- prim_path (str | None): This will check Prim path and its childrens' labels. If None, checks the whole stage.
-
- Returns:
- list[list[str]]: List containing pairs of [prim_path, first_incorrect_label].
- """
- incorrect_pairs = []
- stage = get_current_stage()
- if stage is None:
- logger.warning("Invalid stage, skipping label check")
- return incorrect_pairs
-
- start_prim = stage.GetPrimAtPath(prim_path) if prim_path else stage.GetPseudoRoot()
- if not start_prim:
- if prim_path:
- logger.warning(f"Prim path not found: {prim_path}")
- return incorrect_pairs
-
- prims_to_check = Usd.PrimRange(start_prim)
-
- for prim in prims_to_check:
- if prim.IsA(UsdGeom.Mesh):
- labels_dict = get_labels(prim)
- if labels_dict:
- prim_path_str = prim.GetPath().pathString.lower()
- all_labels = [
- label for sublist in labels_dict.values() for label in sublist if label
- ] # Flatten and filter None/empty
- for label in all_labels:
- label_lower = label.lower()
- # Check if label (or label without separators) is in path
- if (
- label_lower not in prim_path_str
- and label_lower.replace("_", "") not in prim_path_str
- and label_lower.replace("-", "") not in prim_path_str
- ):
- incorrect_pair = [prim.GetPath().pathString, label]
- incorrect_pairs.append(incorrect_pair)
- break # Only report first incorrect label per prim
- return incorrect_pairs
-
-
-def count_labels_in_scene(prim_path: str | None = None) -> dict[str, int]:
- """Returns a dictionary of semantic labels (Semantics.LabelsAPI) and their corresponding count.
-
- Args:
- prim_path (str | None): This will check Prim path and its childrens' labels. If None, checks the whole stage.
-
- Returns:
- dict[str, int]: Dictionary mapping individual labels to their total count across all instances.
- Includes a 'missing_labels' count for meshes with no LabelsAPI.
- """
- labels_counter = {"missing_labels": 0}
- stage = get_current_stage()
- if stage is None:
- logger.warning("Invalid stage, skipping label check")
- return labels_counter
-
- start_prim = stage.GetPrimAtPath(prim_path) if prim_path else stage.GetPseudoRoot()
- if not start_prim:
- if prim_path:
- logger.warning(f"Prim path not found: {prim_path}")
- return labels_counter
-
- prims_to_check = Usd.PrimRange(start_prim)
-
- for prim in prims_to_check:
- if prim.IsA(UsdGeom.Mesh):
- labels_dict = get_labels(prim)
- if not labels_dict:
- labels_counter["missing_labels"] += 1
- else:
- # Iterate through all labels from all instances on the prim
- all_labels = [label for sublist in labels_dict.values() for label in sublist if label]
- for label in all_labels:
- labels_counter[label] = labels_counter.get(label, 0) + 1
-
- return labels_counter
-
-
-def upgrade_prim_semantics_to_labels(prim: Usd.Prim, include_descendants: bool = False) -> int:
- """Upgrades a prim and optionally its descendants from the deprecated SemanticsAPI
- to the new Semantics.LabelsAPI.
-
- Converts each found SemanticsAPI instance on the processed prim(s) to a corresponding
- LabelsAPI instance. The old 'semanticType' becomes the new LabelsAPI
- 'instance_name', and the old 'semanticData' becomes the single label in the
- new 'labels' list. The old SemanticsAPI is always removed after upgrading.
-
- Args:
- prim (Usd.Prim): The starting prim to upgrade.
- include_descendants (bool, optional): If True, upgrades the prim and all its descendants.
- If False (default), upgrades only the specified prim.
-
- Returns:
- int: The total number of SemanticsAPI instances successfully upgraded to LabelsAPI.
- """
- total_upgraded = 0
-
- prims_to_process = Usd.PrimRange(prim) if include_descendants else [prim]
-
- for current_prim in prims_to_process:
- if not current_prim:
- continue
-
- old_semantics = {}
- for prop in current_prim.GetProperties():
- if Semantics.SemanticsAPI.IsSemanticsAPIPath(prop.GetPath()):
- instance_name = prop.SplitName()[1] # Get instance name (e.g., 'Semantics', 'Semantics_a')
- sem_api = Semantics.SemanticsAPI.Get(current_prim, instance_name)
- if sem_api:
- typeAttr = sem_api.GetSemanticTypeAttr()
- dataAttr = sem_api.GetSemanticDataAttr()
- if typeAttr and dataAttr and instance_name not in old_semantics:
- old_semantics[instance_name] = (typeAttr.Get(), dataAttr.Get())
-
- if not old_semantics:
- continue
-
- for old_instance_name, (old_type, old_data) in old_semantics.items():
-
- if not old_type or not old_data:
- logger.warning(
- f"[upgrade_prim] Skipping instance '{old_instance_name}' on {current_prim.GetPath()} due to missing"
- " type or data."
- )
- continue
-
- new_instance_name = old_type
- new_labels = [old_data]
-
- try:
- old_sem_api_to_remove = Semantics.SemanticsAPI.Get(current_prim, old_instance_name)
- if old_sem_api_to_remove:
- typeAttr = old_sem_api_to_remove.GetSemanticTypeAttr()
- dataAttr = old_sem_api_to_remove.GetSemanticDataAttr()
- # Ensure attributes are valid before trying to remove them by name
- if typeAttr and typeAttr.IsDefined():
- current_prim.RemoveProperty(typeAttr.GetName())
- if dataAttr and dataAttr.IsDefined():
- current_prim.RemoveProperty(dataAttr.GetName())
- current_prim.RemoveAPI(Semantics.SemanticsAPI, old_instance_name)
-
- add_labels(current_prim, new_labels, instance_name=new_instance_name, overwrite=False)
-
- total_upgraded += 1
-
- except Exception as e:
- logger.warning(f"Failed to upgrade instance '{old_instance_name}' on {current_prim.GetPath()}: {e}")
- continue
- return total_upgraded
diff --git a/source/isaaclab/isaaclab/sim/utils/stage.py b/source/isaaclab/isaaclab/sim/utils/stage.py
index e7ed1ebfc0b..cfc2018ae00 100644
--- a/source/isaaclab/isaaclab/sim/utils/stage.py
+++ b/source/isaaclab/isaaclab/sim/utils/stage.py
@@ -10,24 +10,22 @@
import typing
from collections.abc import Generator
-import carb
-import omni
-import omni.kit.app
-import usdrt
-from isaacsim.core.utils import stage as sim_stage
-from isaacsim.core.version import get_version
-from omni.metrics.assembler.core import get_metrics_assembler_interface
-from omni.usd.commands import DeletePrimsCommand
+# import carb
+# import omni
+# import omni.kit.app
+# import usdrt
+# from isaacsim.core.utils import stage as sim_stage
+# 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
# import logger
logger = logging.getLogger(__name__)
_context = threading.local() # thread-local storage to handle nested contexts and concurrent access
-# _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
-sim_stage._context = _context
+# Import for remote file handling
+from isaaclab.utils.assets import check_file_path, retrieve_file_path
AXES_TOKEN = {
"X": UsdGeom.Tokens.x,
@@ -61,19 +59,15 @@ def attach_stage_to_usd_context(attaching_early: bool = False):
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
+ import carb
+ import omni.physx
+
# attach stage to physx
stage_id = get_current_stage_id()
physx_sim_interface = omni.physx.get_physx_simulation_interface()
@@ -97,12 +91,11 @@ def attach_stage_to_usd_context(attaching_early: bool = False):
# 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)
+ import omni.usd
+
# attach stage to usd context
omni.usd.get_context().attach_stage_with_callback(stage_id)
@@ -110,9 +103,6 @@ def attach_stage_to_usd_context(attaching_early: bool = False):
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.
@@ -126,6 +116,8 @@ def is_current_stage_in_memory() -> bool:
# grab current stage id
stage_id = get_current_stage_id()
+ import omni.usd
+
# grab context stage id
context_stage = omni.usd.get_context().get_stage()
with use_stage(context_stage):
@@ -137,9 +129,10 @@ def is_current_stage_in_memory() -> bool:
@contextlib.contextmanager
def use_stage(stage: Usd.Stage) -> Generator[None, None, None]:
- """Context manager that sets a thread-local stage, if supported.
+ """Context manager that sets a thread-local stage.
- In Isaac Sim < 5.0, this is a no-op to maintain compatibility.
+ This allows different threads or nested contexts to use different USD stages
+ without interfering with each other.
Args:
stage: The stage to set temporarily.
@@ -160,35 +153,39 @@ def use_stage(stage: Usd.Stage) -> Generator[None, None, None]:
... pass
>>> # operate on the default stage attached to the USD context
"""
- isaac_sim_version = float(".".join(get_version()[2]))
- if isaac_sim_version < 5:
- logger.warning("[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:
+ # 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:
+ if hasattr(_context, "stage"):
delattr(_context, "stage")
- else:
- _context.stage = previous_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
+def get_current_stage(fabric: bool = False) -> Usd.Stage:
+ """Get the current open USD stage.
+
+ This function retrieves the current USD stage using the following priority:
+ 1. Thread-local stage context (set via use_stage context manager)
+ 2. SimulationContext singleton's stage (if initialized)
+ 3. USD StageCache (standard USD way to track open stages)
Args:
- fabric: True to get the fabric stage. False to get the USD stage. Defaults to False.
+ fabric: Deprecated parameter, kept for backward compatibility. Defaults to False.
+
+ Raises:
+ RuntimeError: If no USD stage is currently open.
Returns:
- The USD or Fabric stage as specified by the input arg fabric.
+ The USD stage.
Example:
@@ -201,14 +198,44 @@ def get_current_stage(fabric: bool = False) -> Usd.Stage | usdrt.Usd._Usd.Stage:
sessionLayer=Sdf.Find('anon:0x7fba6c01c5c0:World7-session.usda'),
pathResolverContext=)
"""
- stage = getattr(_context, "stage", omni.usd.get_context().get_stage())
+
+ # Try to get stage from thread-local context first
+ stage = getattr(_context, "stage", None)
+
if fabric:
+ import usdrt
+
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
+
+ if stage is not None:
+ return stage
+
+ # Try to get stage from SimulationContext singleton (if initialized)
+ try:
+ # Import here to avoid circular dependency
+ from isaaclab.sim.simulation_context import SimulationContext
+
+ sim_context = SimulationContext.instance()
+ if sim_context is not None and hasattr(sim_context, "stage") and sim_context.stage is not None:
+ return sim_context.stage
+ except (ImportError, RuntimeError):
+ # SimulationContext may not be initialized yet
+ pass
+
+ # Fall back to USD StageCache - get the first stage in the cache
+ # This is the standard USD way to track open stages
+ stage_cache = UsdUtils.StageCache.Get()
+ if stage_cache.Size() > 0:
+ # Get all stages and return the first one (most recently accessed)
+ all_stages = stage_cache.GetAllStages()
+ if all_stages:
+ return all_stages[0]
+
+ raise RuntimeError("No USD stage is currently open. Please create a stage first.")
def get_current_stage_id() -> int:
@@ -245,6 +272,8 @@ def update_stage() -> None:
>>>
>>> stage_utils.update_stage()
"""
+ import omni.kit.app
+
omni.kit.app.get_app_interface().update()
@@ -326,6 +355,8 @@ def default_predicate(prim: Usd.Prim) -> bool:
return False
if prim.GetMetadata("hide_in_stage_window"):
return False
+ import omni.usd
+
if omni.usd.check_ancestral(prim):
return False
return True
@@ -340,15 +371,22 @@ def predicate_from_path(prim: Usd.Prim) -> bool:
else:
prims = get_all_matching_child_prims("/", predicate_from_path)
prim_paths_to_delete = [prim.GetPath().pathString for prim in prims]
+ from omni.usd.commands import DeletePrimsCommand
+
DeletePrimsCommand(prim_paths_to_delete).do()
if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False:
+ import omni.kit.app
+
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.
+ Args:
+ fabric: Deprecated parameter, kept for backward compatibility. Defaults to False.
+
Example:
.. code-block:: python
@@ -380,10 +418,15 @@ def add_reference_to_stage(usd_path: str, prim_path: str, prim_type: str = "Xfor
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.
+
+ This function supports both local and remote USD files (HTTP, HTTPS, S3). Remote files
+ are automatically downloaded to a local cache before being referenced.
+
+ Note:
+ This is a USD-core only implementation that does not use omni APIs for metrics checking.
Args:
- usd_path: The path to USD file to reference.
+ usd_path: The path to USD file to reference. Can be a local path or remote URL (HTTP, HTTPS, S3).
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".
@@ -399,43 +442,78 @@ def add_reference_to_stage(usd_path: str, prim_path: str, prim_type: str = "Xfor
>>> import isaaclab.sim.utils.stage as stage_utils
>>>
- >>> # load an USD file (franka.usd) to the stage under the path /World/panda
+ >>> # load a local USD file
>>> prim = stage_utils.add_reference_to_stage(
... usd_path="/home//Documents/Assets/Robots/FrankaRobotics/FrankaPanda/franka.usd",
... prim_path="/World/panda"
... )
>>> prim
Usd.Prim()
+ >>>
+ >>> # load a remote USD file from S3
+ >>> prim = stage_utils.add_reference_to_stage(
+ ... usd_path="https://s3.amazonaws.com/bucket/robot.usd",
+ ... prim_path="/World/robot"
+ ... )
"""
+ # Store original path for error messages
+ original_usd_path = usd_path
+
+ # Check if file is remote and download if needed
+ # check_file_path returns: 0 (not found), 1 (local), 2 (remote)
+ file_status = check_file_path(usd_path)
+
+ if file_status == 0:
+ raise FileNotFoundError(f"USD file not found at path: {usd_path}")
+
+ # Download remote files to local cache
+ if file_status == 2:
+ logger.info(f"Downloading remote USD file: {original_usd_path}")
+ try:
+ usd_path = retrieve_file_path(usd_path, force_download=False)
+ logger.info(f" Downloaded to: {usd_path}")
+ except Exception as e:
+ raise FileNotFoundError(f"Failed to download USD file from {original_usd_path}: {e}")
+
+ # Verify the local file exists and can be opened
+ import os
+
+ if not os.path.exists(usd_path):
+ raise FileNotFoundError(f"USD file does not exist at local path: {usd_path} (original: {original_usd_path})")
+
stage = get_current_stage()
prim = stage.GetPrimAtPath(prim_path)
if not prim.IsValid():
prim = stage.DefinePrim(prim_path, prim_type)
- # logger.info("Loading Asset from path {} ".format(usd_path))
- # Handle units
+
+ # Try to open the USD layer with the local path
sdf_layer = Sdf.Layer.FindOrOpen(usd_path)
if not sdf_layer:
- pass
- # logger.info(f"Could not get Sdf layer for {usd_path}")
- else:
+ raise FileNotFoundError(f"Could not open USD file at {usd_path} (original: {original_usd_path})")
+
+ # Attempt to use omni metrics assembler for unit checking (if available)
+ try:
+ from omni.metrics.assembler.core import get_metrics_assembler_interface
+
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:
- 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")
+ # Metrics check passed, add reference using pure USD API
+ success_bool = prim.GetReferences().AddReference(usd_path)
+ if not success_bool:
+ raise FileNotFoundError(f"Failed to add reference to {usd_path}")
else:
+ # Metrics check didn't pass, use pure USD
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")
+ raise FileNotFoundError(f"Failed to add reference to {usd_path}")
+ except (ImportError, Exception):
+ # Omni APIs not available or failed, fall back to pure USD implementation
+ success_bool = prim.GetReferences().AddReference(usd_path)
+ if not success_bool:
+ raise FileNotFoundError(f"Failed to add reference to {usd_path}")
return prim
@@ -457,11 +535,16 @@ def create_new_stage() -> Usd.Stage:
sessionLayer=Sdf.Find('anon:0x7fba6c01c5c0:World7-session.usda'),
pathResolverContext=)
"""
+ import omni.usd
+
return omni.usd.get_context().new_stage()
def create_new_stage_in_memory() -> Usd.Stage:
- """Creates a new stage in memory, if supported.
+ """Creates a new stage in memory using USD core APIs.
+
+ This function creates a stage in memory and adds it to the USD StageCache
+ so it can be properly tracked and retrieved by get_current_stage().
Returns:
The new stage in memory.
@@ -477,15 +560,15 @@ def create_new_stage_in_memory() -> Usd.Stage:
sessionLayer=Sdf.Find('anon:0xf7cd2e0:tmp-session.usda'),
pathResolverContext=)
"""
- isaac_sim_version = float(".".join(get_version()[2]))
- if isaac_sim_version < 5:
- logger.warning(
- "[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()
+ # Create a new stage in memory using USD core API
+ stage = Usd.Stage.CreateInMemory()
+
+ # Add to StageCache so it can be found by get_current_stage()
+ # This ensures the stage is properly tracked and can be retrieved later
+ stage_cache = UsdUtils.StageCache.Get()
+ stage_cache.Insert(stage)
+
+ return stage
def open_stage(usd_path: str) -> bool:
@@ -509,6 +592,8 @@ def open_stage(usd_path: str) -> bool:
>>> stage_utils.open_stage("/home//Documents/Assets/Robots/FrankaRobotics/FrankaPanda/franka.usd")
True
"""
+ import omni.usd
+
if not Usd.Stage.IsSupportedFile(usd_path):
raise ValueError("Only USD files can be loaded with this method")
usd_context = omni.usd.get_context()
@@ -543,6 +628,8 @@ def save_stage(usd_path: str, save_and_reload_in_place=True) -> bool:
if not Usd.Stage.IsSupportedFile(usd_path):
raise ValueError("Only USD files can be saved with this method")
+ import omni.usd
+
layer = Sdf.Layer.CreateNew(usd_path)
root_layer = get_current_stage().GetRootLayer()
layer.TransferContent(root_layer)
@@ -589,6 +676,8 @@ def close_stage(callback_fn: typing.Callable | None = None) -> bool:
callback: (False, 'Stage opening or closing already in progress!!') {}
False
"""
+ import omni.usd
+
if callback_fn is None:
result = omni.usd.get_context().close_stage()
else:
@@ -599,6 +688,9 @@ def close_stage(callback_fn: typing.Callable | None = None) -> bool:
def traverse_stage(fabric=False) -> typing.Iterable:
"""Traverse through prims (hidden or not) in the opened Usd stage.
+ Args:
+ fabric: Deprecated parameter, kept for backward compatibility. Defaults to False.
+
Returns:
Generator which yields prims from the stage in depth-first-traversal order.
@@ -640,6 +732,8 @@ def is_stage_loading() -> bool:
>>> stage_utils.is_stage_loading()
False
"""
+ import omni.usd
+
context = omni.usd.get_context()
if context is None:
return False
@@ -739,6 +833,8 @@ def get_next_free_path(path: str, parent: str = None) -> str:
>>> stage_utils.get_next_free_path("/World/Cube")
/World/Cube_02
"""
+ import omni.usd
+
if parent is not None:
# remove trailing slash from parent and leading slash from path
path = omni.usd.get_stage_next_free_path(
diff --git a/source/isaaclab/isaaclab/ui/widgets/line_plot.py b/source/isaaclab/isaaclab/ui/widgets/line_plot.py
index e31410e6b6b..87b575ea78a 100644
--- a/source/isaaclab/isaaclab/ui/widgets/line_plot.py
+++ b/source/isaaclab/isaaclab/ui/widgets/line_plot.py
@@ -11,7 +11,8 @@
from typing import TYPE_CHECKING
import omni
-from isaacsim.core.api.simulation_context import SimulationContext
+
+from isaaclab.sim.simulation_context import SimulationContext
with suppress(ImportError):
# isaacsim.gui is not available when running in headless mode.
@@ -69,6 +70,7 @@ def __init__(
show_legend: bool = True,
legends: list[str] | None = None,
max_datapoints: int = 200,
+ dt: float | None = None,
):
"""Create a new LiveLinePlot widget.
@@ -80,6 +82,7 @@ def __init__(
show_legend: Whether to display the legend. Defaults to True.
legends: A list of strings containing the legend labels for each series. If None, the default labels are "Series_0", "Series_1", etc. Defaults to None.
max_datapoints: The maximum number of data points to display. If the number of data points exceeds this value, the oldest data points are removed. Defaults to 200.
+ dt: Time delta between samples for derivative computation. If None, will attempt to use SimulationContext.instance().get_rendering_dt() if available. Defaults to None.
"""
super().__init__(self._create_ui_widget())
self.plot_height = plot_height
@@ -100,6 +103,7 @@ def __init__(
self._filter_mode = None
self._last_values = None
self._is_paused = False
+ self._dt = dt
# Gets populated when widget is built
self._main_plot_frame = None
@@ -144,7 +148,7 @@ def clear(self):
# self._container_frame.rebuild()
- def add_datapoint(self, y_coords: list[float]):
+ def add_datapoint(self, y_coords: list[float], dt: float | None = None):
"""Add a data point to the plot.
The data point is added to the end of the plot. If the number of data points exceeds the maximum number
@@ -154,6 +158,7 @@ def add_datapoint(self, y_coords: list[float]):
Args:
y_coords: A list of floats containing the y coordinates of the new data points.
+ dt: Time delta for this data point. If None, uses the dt from constructor or SimulationContext. Defaults to None.
"""
for idx, y_coord in enumerate(y_coords):
@@ -170,7 +175,12 @@ def add_datapoint(self, y_coords: list[float]):
y_coord = self._y_data[idx][-1] + y_coord
elif self._filter_mode == "Derivative":
if self._last_values is not None:
- y_coord = (y_coord - self._last_values[idx]) / SimulationContext.instance().get_rendering_dt()
+ # Use provided dt, fall back to stored dt, then to SimulationContext
+ time_delta = dt if dt is not None else self._dt
+ if time_delta is None:
+ # Fall back to SimulationContext only if no dt is provided
+ time_delta = SimulationContext.instance().get_rendering_dt()
+ y_coord = (y_coord - self._last_values[idx]) / time_delta
self._y_data[idx].append(float(y_coord))
diff --git a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py
index 28f62f55765..29dfaa8ecd6 100644
--- a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py
+++ b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py
@@ -11,10 +11,8 @@
from dataclasses import MISSING
from typing import TYPE_CHECKING
-import omni.kit.app
-from isaacsim.core.api.simulation_context import SimulationContext
-
from isaaclab.managers import ManagerBase
+from isaaclab.sim.simulation_context import SimulationContext
from isaaclab.utils import configclass
from .image_plot import ImagePlot
@@ -185,6 +183,8 @@ def _set_debug_vis_impl(self, debug_vis: bool):
debug_vis: Whether to enable or disable debug visualization.
"""
+ import omni.kit.app
+
if not hasattr(self, "_vis_frame"):
raise RuntimeError("No frame set for debug visualization.")
diff --git a/source/isaaclab/isaaclab/utils/assets.py b/source/isaaclab/isaaclab/utils/assets.py
index 2318a9be55c..8f9a43d702e 100644
--- a/source/isaaclab/isaaclab/utils/assets.py
+++ b/source/isaaclab/isaaclab/utils/assets.py
@@ -14,15 +14,21 @@
"""
import io
+import logging
import os
+import posixpath
import tempfile
+from pathlib import Path
from typing import Literal
+from urllib.parse import urlparse
-import carb
import omni.client
-NUCLEUS_ASSET_ROOT_DIR = carb.settings.get_settings().get("/persistent/isaac/asset_root/cloud")
-"""Path to the root directory on the Nucleus Server."""
+logger = logging.getLogger(__name__)
+from pxr import Sdf
+
+NUCLEUS_ASSET_ROOT_DIR = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/5.0"
+"""Path to the root directory on the cloud storage."""
NVIDIA_NUCLEUS_DIR = f"{NUCLEUS_ASSET_ROOT_DIR}/NVIDIA"
"""Path to the root directory on the NVIDIA Nucleus Server."""
@@ -33,6 +39,8 @@
ISAACLAB_NUCLEUS_DIR = f"{ISAAC_NUCLEUS_DIR}/IsaacLab"
"""Path to the ``Isaac/IsaacLab`` directory on the NVIDIA Nucleus Server."""
+USD_EXTENSIONS = {".usd", ".usda", ".usdz"}
+
def check_file_path(path: str) -> Literal[0, 1, 2]:
"""Checks if a file exists on the Nucleus Server or locally.
@@ -91,16 +99,38 @@ def retrieve_file_path(path: str, download_dir: str | None = None, force_downloa
# create download directory if it does not exist
if not os.path.exists(download_dir):
os.makedirs(download_dir)
- # download file in temp directory using os
- file_name = os.path.basename(omni.client.break_url(path.replace(os.sep, "/")).path)
- target_path = os.path.join(download_dir, file_name)
- # check if file already exists locally
- if not os.path.isfile(target_path) or force_download:
- # copy file to local machine
- result = omni.client.copy(path.replace(os.sep, "/"), target_path, omni.client.CopyBehavior.OVERWRITE)
- if result != omni.client.Result.OK and force_download:
- raise RuntimeError(f"Unable to copy file: '{path}'. Is the Nucleus Server running?")
- return os.path.abspath(target_path)
+ # recursive download: mirror remote tree under download_dir
+ remote_url = path.replace(os.sep, "/")
+ to_visit = [remote_url]
+ visited = set()
+ local_root = None
+
+ while to_visit:
+ cur_url = to_visit.pop()
+ if cur_url in visited:
+ continue
+ visited.add(cur_url)
+
+ cur_rel = urlparse(cur_url).path.lstrip("/")
+ target_path = os.path.join(download_dir, cur_rel)
+ os.makedirs(os.path.dirname(target_path), exist_ok=True)
+
+ if not os.path.isfile(target_path) or force_download:
+ result = omni.client.copy(cur_url, target_path, omni.client.CopyBehavior.OVERWRITE)
+ if result != omni.client.Result.OK and force_download:
+ raise RuntimeError(f"Unable to copy file: '{cur_url}'. Is the Nucleus Server running?")
+
+ if local_root is None:
+ local_root = target_path
+
+ # recurse into USD dependencies and referenced assets
+ if Path(target_path).suffix.lower() in USD_EXTENSIONS:
+ for ref in _find_usd_references(target_path):
+ ref_url = _resolve_reference_url(cur_url, ref)
+ if ref_url and ref_url not in visited:
+ to_visit.append(ref_url)
+
+ return os.path.abspath(local_root)
else:
raise FileNotFoundError(f"Unable to find the file: {path}")
@@ -127,3 +157,102 @@ def read_file(path: str) -> io.BytesIO:
return io.BytesIO(memoryview(file_content).tobytes())
else:
raise FileNotFoundError(f"Unable to find the file: {path}")
+
+
+def _is_downloadable_asset(path: str) -> bool:
+ """Return True for USD or other asset types we mirror locally (textures, etc.)."""
+ clean = path.split("?", 1)[0].split("#", 1)[0]
+ suffix = Path(clean).suffix.lower()
+
+ if suffix == ".mdl":
+ # MDL modules (OmniPBR.mdl, OmniSurface.mdl, ...) come from MDL search paths
+ return False
+ if not suffix:
+ return False
+ if suffix not in {".usd", ".usda", ".usdz", ".png", ".jpg", ".jpeg", ".exr", ".hdr", ".tif", ".tiff"}:
+ return False
+ return True
+
+
+def _find_usd_references(local_usd_path: str) -> set[str]:
+ """Use Sdf API to collect referenced assets from a USD layer."""
+ try:
+ layer = Sdf.Layer.FindOrOpen(local_usd_path)
+ except Exception:
+ logger.warning("Failed to open USD layer: %s", local_usd_path, exc_info=True)
+ return set()
+
+ if layer is None:
+ return set()
+
+ refs: set[str] = set()
+
+ # Sublayers
+ for sub_path in getattr(layer, "subLayerPaths", []) or []:
+ if sub_path and _is_downloadable_asset(sub_path):
+ refs.add(str(sub_path))
+
+ def _walk_prim(prim_spec: Sdf.PrimSpec) -> None:
+ # References
+ ref_list = prim_spec.referenceList
+ for field in ("addedItems", "prependedItems", "appendedItems", "explicitItems"):
+ items = getattr(ref_list, field, None)
+ if not items:
+ continue
+ for ref in items:
+ asset_path = getattr(ref, "assetPath", None)
+ if asset_path and _is_downloadable_asset(asset_path):
+ refs.add(str(asset_path))
+
+ # Payloads
+ payload_list = prim_spec.payloadList
+ for field in ("addedItems", "prependedItems", "appendedItems", "explicitItems"):
+ items = getattr(payload_list, field, None)
+ if not items:
+ continue
+ for payload in items:
+ asset_path = getattr(payload, "assetPath", None)
+ if asset_path and _is_downloadable_asset(asset_path):
+ refs.add(str(asset_path))
+
+ # AssetPath-valued attributes (this is where OmniPBR.mdl, textures, etc. show up)
+ for attr_spec in prim_spec.attributes.values():
+ default = attr_spec.default
+ if isinstance(default, Sdf.AssetPath):
+ if default.path and _is_downloadable_asset(default.path):
+ refs.add(default.path)
+ elif isinstance(default, Sdf.AssetPathArray):
+ for ap in default:
+ if ap.path and _is_downloadable_asset(ap.path):
+ refs.add(ap.path)
+
+ for child in prim_spec.nameChildren.values():
+ _walk_prim(child)
+
+ for root_prim in layer.rootPrims.values():
+ _walk_prim(root_prim)
+
+ return refs
+
+
+def _resolve_reference_url(base_url: str, ref: str) -> str:
+ """Resolve a USD asset reference against a base URL (http/local)."""
+ ref = ref.strip()
+ if not ref:
+ return ref
+
+ parsed_ref = urlparse(ref)
+ if parsed_ref.scheme:
+ return ref
+
+ base = urlparse(base_url)
+ if base.scheme == "":
+ base_dir = os.path.dirname(base_url)
+ return os.path.normpath(os.path.join(base_dir, ref))
+
+ base_dir = posixpath.dirname(base.path)
+ if ref.startswith("/"):
+ new_path = posixpath.normpath(ref)
+ else:
+ new_path = posixpath.normpath(posixpath.join(base_dir, ref))
+ return f"{base.scheme}://{base.netloc}{new_path}"
diff --git a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py
index adb19ee578a..8d8b296b5c4 100644
--- a/source/isaaclab/isaaclab/visualizers/ov_visualizer.py
+++ b/source/isaaclab/isaaclab/visualizers/ov_visualizer.py
@@ -127,6 +127,34 @@ def supports_live_plots(self) -> bool:
"""
return True
+ def set_camera_view(
+ self, eye: tuple[float, float, float] | list[float], target: tuple[float, float, float] | list[float]
+ ) -> None:
+ """Set the viewport camera position and target.
+
+ This method positions the viewport camera at the specified eye location and orients it to look at
+ the target location. It uses the active camera of the viewport managed by this visualizer.
+
+ Args:
+ eye: Camera position in world coordinates (x, y, z).
+ target: Target/look-at position in world coordinates (x, y, z).
+
+ Example:
+
+ .. code-block:: python
+
+ # Set camera to look at the origin from position (2.5, 2.5, 2.5)
+ >>> visualizer.set_camera_view(
+ ... eye=[2.5, 2.5, 2.5],
+ ... target=[0.0, 0.0, 0.0],
+ ... )
+ """
+ if not self._is_initialized:
+ logger.warning("[OVVisualizer] Cannot set camera view - visualizer not initialized.")
+ return
+
+ self._set_viewport_camera(tuple(eye), tuple(target))
+
# ------------------------------------------------------------------
# Private methods
# ------------------------------------------------------------------
diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py
index d0eae704865..c08106d611a 100644
--- a/source/isaaclab/setup.py
+++ b/source/isaaclab/setup.py
@@ -57,6 +57,9 @@
# newer versions of rerun, like 0.27, don't have this issue, but require numpy >=2
# kelly: seems like we can run with numpy >= 2 so far, if issues arise, we can revert back to 0.23
"rerun-sdk==0.27",
+ # replacements of omni.client and nucleus
+ "boto3",
+ "requests",
]
# Additional dependencies that are only available on Linux platforms
diff --git a/tools/installation/install_omni_client_packman.py b/tools/installation/install_omni_client_packman.py
new file mode 100755
index 00000000000..84beb2bedd9
--- /dev/null
+++ b/tools/installation/install_omni_client_packman.py
@@ -0,0 +1,128 @@
+#!/usr/bin/env python3
+# 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
+
+"""
+Install omni.client from a prebuilt 7z payload into the current Python environment.
+
+- Downloads https://d4i3qtqj3r0z5.cloudfront.net/omni_client_library.linux-x86_64@.7z
+- Extracts to a cache dir (default: $TMPDIR/omni_client_cache; override with OMNI_CLIENT_CACHE)
+- Copies the Python package (release/bindings-python) and native libs (release/*.so) into site-packages/_omni_client
+- Drops a .pth for import visibility
+- Creates a minimal dist-info so `pip uninstall omni-client-offline` works
+
+# TODO: Once pip has been shipped, remove this script and use pip install omniverseclient== instead.
+"""
+
+import logging
+import os
+import pathlib
+import shutil
+import site
+import subprocess
+import sys
+import tempfile
+import urllib.request
+
+# Ensure py7zr is available
+try:
+ import py7zr # type: ignore # noqa: F401
+except ImportError:
+ subprocess.check_call([sys.executable, "-m", "pip", "install", "py7zr"])
+ import py7zr # type: ignore
+
+
+logger = logging.getLogger(__name__)
+
+# Configuration
+pkg_ver = os.environ.get("OMNI_CLIENT_VERSION", "2.68.1")
+cache_root = pathlib.Path(os.environ.get("OMNI_CLIENT_CACHE", tempfile.gettempdir())) / "omni_client_cache"
+payload_url = f"https://d4i3qtqj3r0z5.cloudfront.net/omni_client_library.linux-x86_64%40{pkg_ver}.7z"
+
+# Paths
+cache_root.mkdir(parents=True, exist_ok=True)
+payload = cache_root / f"omni_client.{pkg_ver}.7z"
+extract_root = cache_root / f"omni_client.{pkg_ver}.extracted"
+
+# Download payload if missing
+if not payload.exists():
+ logger.info(f" Downloading omni.client payload from {payload_url} ...")
+ urllib.request.urlretrieve(payload_url, payload)
+
+# Extract payload only if not already present
+extract_root.mkdir(parents=True, exist_ok=True)
+already_extracted = (extract_root / "release" / "bindings-python" / "omni" / "client").exists()
+if not already_extracted:
+ logger.info(f" Extracting omni.client payload into {extract_root} ...")
+ with py7zr.SevenZipFile(payload, mode="r") as z:
+ z.extractall(path=extract_root)
+else:
+ logger.info(f" Reusing existing extraction at {extract_root}")
+
+# Locate python package and native libs
+src_py = extract_root / "release" / "bindings-python"
+if not (src_py / "omni" / "client").exists():
+ raise RuntimeError(f"Could not locate omni.client python package at {src_py}")
+
+src_lib = extract_root / "release"
+if not any(src_lib.glob("libomni*.so*")):
+ raise RuntimeError(f"Could not locate native libs under {src_lib}")
+
+# Install into site-packages
+if hasattr(site, "getsitepackages"):
+ candidates = [pathlib.Path(p) for p in site.getsitepackages() if p.startswith(sys.prefix)]
+ site_pkgs = candidates[0] if candidates else pathlib.Path(site.getusersitepackages())
+else:
+ site_pkgs = pathlib.Path(site.getusersitepackages())
+dest = site_pkgs / "_omni_client"
+dest.mkdir(parents=True, exist_ok=True)
+shutil.copytree(src_py, dest, dirs_exist_ok=True)
+shutil.copytree(src_lib, dest / "lib", dirs_exist_ok=True)
+
+# Ensure the extension can find its libs without env vars
+client_dir = dest / "omni" / "client"
+client_dir.mkdir(parents=True, exist_ok=True)
+for libfile in (dest / "lib").glob("libomni*.so*"):
+ target = client_dir / libfile.name
+ if not target.exists():
+ try:
+ target.symlink_to(libfile)
+ except Exception:
+ shutil.copy2(libfile, target)
+
+# Add .pth for import visibility
+with open(site_pkgs / "omni_client.pth", "w", encoding="utf-8") as f:
+ f.write(str(dest) + "\n")
+ f.write(str(dest / "lib") + "\n")
+
+# Minimal dist-info so pip can uninstall (pip uninstall omni-client)
+dist_name = "omni-client"
+dist_info = site_pkgs / f"{dist_name.replace('-', '_')}-{pkg_ver}.dist-info"
+dist_info.mkdir(parents=True, exist_ok=True)
+(dist_info / "INSTALLER").write_text("manual\n", encoding="utf-8")
+metadata = "\n".join([
+ f"Name: {dist_name}",
+ f"Version: {pkg_ver}",
+ "Summary: Offline omni.client bundle",
+ "",
+])
+(dist_info / "METADATA").write_text(metadata, encoding="utf-8")
+
+records = []
+for path in [
+ site_pkgs / "omni_client.pth",
+ dist_info / "INSTALLER",
+ dist_info / "METADATA",
+]:
+ records.append(f"{path.relative_to(site_pkgs)},,")
+for path in dest.rglob("*"):
+ records.append(f"{path.relative_to(site_pkgs)},,")
+for path in dist_info.rglob("*"):
+ if path.name != "RECORD":
+ records.append(f"{path.relative_to(site_pkgs)},,")
+(dist_info / "RECORD").write_text("\n".join(records), encoding="utf-8")
+
+logger.info(f"Installed omni.client to {dest} (dist: {dist_info.name})")
+logger.info("Uninstall with: pip uninstall omni-client")