diff --git a/docs/conf.py b/docs/conf.py index 00d7af5ae59..a571faed796 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -157,6 +157,7 @@ "omni.client", "omni.physx", "omni.physics", + "usdrt", "pxr.PhysxSchema", "pxr.PhysicsSchemaTools", "omni.replicator", diff --git a/scripts/benchmarks/benchmark_cameras.py b/scripts/benchmarks/benchmark_cameras.py index f8ec527ef29..89c25e87088 100644 --- a/scripts/benchmarks/benchmark_cameras.py +++ b/scripts/benchmarks/benchmark_cameras.py @@ -245,11 +245,10 @@ import time import torch -import isaacsim.core.utils.prims as prim_utils import psutil -from isaacsim.core.utils.stage import create_new_stage import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.scene.interactive_scene import InteractiveScene from isaaclab.sensors import ( @@ -261,6 +260,7 @@ TiledCameraCfg, patterns, ) +from isaaclab.sim.utils.stage import create_new_stage from isaaclab.utils.math import orthogonalize_perspective_depth, unproject_depth from isaaclab_tasks.utils import load_cfg_from_registry diff --git a/scripts/benchmarks/benchmark_non_rl.py b/scripts/benchmarks/benchmark_non_rl.py index adc797e7f5e..f84a63270be 100644 --- a/scripts/benchmarks/benchmark_non_rl.py +++ b/scripts/benchmarks/benchmark_non_rl.py @@ -55,14 +55,9 @@ """Rest everything follows.""" -# enable benchmarking extension -from isaacsim.core.utils.extensions import enable_extension - -enable_extension("isaacsim.benchmark.services") -from isaacsim.benchmark.services import BaseIsaacBenchmark - sys.path.append(os.path.join(os.path.dirname(os.path.abspath(__file__)), "../..")) +from isaaclab import lazy from isaaclab.utils.timer import Timer from scripts.benchmarks.utils import ( log_app_start_time, @@ -90,9 +85,10 @@ imports_time_end = time.perf_counter_ns() - +# enable benchmarking extension +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.benchmark.services") # Create the benchmark -benchmark = BaseIsaacBenchmark( +benchmark = lazy.isaacsim.benchmark.services.BaseIsaacBenchmark( benchmark_name="benchmark_non_rl", workflow_metadata={ "metadata": [ @@ -109,7 +105,6 @@ @hydra_task_config(args_cli.task, None) def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agent_cfg: dict): """Benchmark without RL in the loop.""" - # override configurations with non-hydra CLI arguments env_cfg.scene.num_envs = args_cli.num_envs if args_cli.num_envs is not None else env_cfg.scene.num_envs env_cfg.sim.device = args_cli.device if args_cli.device is not None else env_cfg.sim.device diff --git a/scripts/benchmarks/benchmark_rlgames.py b/scripts/benchmarks/benchmark_rlgames.py index c142af86185..b9e46e7b61f 100644 --- a/scripts/benchmarks/benchmark_rlgames.py +++ b/scripts/benchmarks/benchmark_rlgames.py @@ -54,12 +54,6 @@ """Rest everything follows.""" -# enable benchmarking extension -from isaacsim.core.utils.extensions import enable_extension - -enable_extension("isaacsim.benchmark.services") -from isaacsim.benchmark.services import BaseIsaacBenchmark - imports_time_begin = time.perf_counter_ns() import gymnasium as gym @@ -73,6 +67,7 @@ from rl_games.common.algo_observer import IsaacAlgoObserver from rl_games.torch_runner import Runner +from isaaclab import lazy from isaaclab.envs import DirectMARLEnvCfg, DirectRLEnvCfg, ManagerBasedRLEnvCfg from isaaclab.utils.dict import print_dict from isaaclab.utils.io import dump_yaml @@ -106,8 +101,10 @@ torch.backends.cudnn.benchmark = False +# enable benchmarking extension +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.benchmark.services") # Create the benchmark -benchmark = BaseIsaacBenchmark( +benchmark = lazy.isaacsim.benchmark.services.BaseIsaacBenchmark( benchmark_name="benchmark_rlgames_train", workflow_metadata={ "metadata": [ diff --git a/scripts/benchmarks/benchmark_rsl_rl.py b/scripts/benchmarks/benchmark_rsl_rl.py index 506559fb442..4d3795b9520 100644 --- a/scripts/benchmarks/benchmark_rsl_rl.py +++ b/scripts/benchmarks/benchmark_rsl_rl.py @@ -85,11 +85,8 @@ imports_time_end = time.perf_counter_ns() -from isaacsim.core.utils.extensions import enable_extension - -enable_extension("isaacsim.benchmark.services") -from isaacsim.benchmark.services import BaseIsaacBenchmark +from isaaclab import lazy from isaaclab.utils.timer import Timer from scripts.benchmarks.utils import ( log_app_start_time, @@ -109,8 +106,10 @@ torch.backends.cudnn.deterministic = False torch.backends.cudnn.benchmark = False +# enable benchmarking extension +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.benchmark.services") # Create the benchmark -benchmark = BaseIsaacBenchmark( +benchmark = lazy.isaacsim.benchmark.services.BaseIsaacBenchmark( benchmark_name="benchmark_rsl_rl_train", workflow_metadata={ "metadata": [ diff --git a/scripts/benchmarks/utils.py b/scripts/benchmarks/utils.py index ff2ca5c0114..a64d0fbf30b 100644 --- a/scripts/benchmarks/utils.py +++ b/scripts/benchmarks/utils.py @@ -6,11 +6,12 @@ import glob import os +from typing import Any -from isaacsim.benchmark.services import BaseIsaacBenchmark -from isaacsim.benchmark.services.metrics.measurements import DictMeasurement, ListMeasurement, SingleMeasurement from tensorboard.backend.event_processing import event_accumulator +from isaaclab import lazy + def parse_tf_logs(log_dir: str): """Search for the latest tfevents file in log_dir folder and returns @@ -36,59 +37,65 @@ def parse_tf_logs(log_dir: str): return log_data -############################# -# logging benchmark metrics # -############################# - - -def log_min_max_mean_stats(benchmark: BaseIsaacBenchmark, values: dict): +def log_min_max_mean_stats(benchmark: Any, values: dict): + metrics_mod = lazy.isaacsim.benchmark.services.metrics.measurements for k, v in values.items(): - measurement = SingleMeasurement(name=f"Min {k}", value=min(v), unit="ms") + measurement = metrics_mod.SingleMeasurement(name=f"Min {k}", value=min(v), unit="ms") benchmark.store_custom_measurement("runtime", measurement) - measurement = SingleMeasurement(name=f"Max {k}", value=max(v), unit="ms") + measurement = metrics_mod.SingleMeasurement(name=f"Max {k}", value=max(v), unit="ms") benchmark.store_custom_measurement("runtime", measurement) - measurement = SingleMeasurement(name=f"Mean {k}", value=sum(v) / len(v), unit="ms") + measurement = metrics_mod.SingleMeasurement(name=f"Mean {k}", value=sum(v) / len(v), unit="ms") benchmark.store_custom_measurement("runtime", measurement) -def log_app_start_time(benchmark: BaseIsaacBenchmark, value: float): +def log_app_start_time(benchmark: Any, value: float): + SingleMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.SingleMeasurement measurement = SingleMeasurement(name="App Launch Time", value=value, unit="ms") benchmark.store_custom_measurement("startup", measurement) -def log_python_imports_time(benchmark: BaseIsaacBenchmark, value: float): +def log_python_imports_time(benchmark: Any, value: float): + SingleMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.SingleMeasurement measurement = SingleMeasurement(name="Python Imports Time", value=value, unit="ms") benchmark.store_custom_measurement("startup", measurement) -def log_task_start_time(benchmark: BaseIsaacBenchmark, value: float): +def log_task_start_time(benchmark: Any, value: float): + SingleMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.SingleMeasurement measurement = SingleMeasurement(name="Task Creation and Start Time", value=value, unit="ms") benchmark.store_custom_measurement("startup", measurement) -def log_scene_creation_time(benchmark: BaseIsaacBenchmark, value: float): +def log_scene_creation_time(benchmark: Any, value: float): + SingleMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.SingleMeasurement measurement = SingleMeasurement(name="Scene Creation Time", value=value, unit="ms") benchmark.store_custom_measurement("startup", measurement) -def log_simulation_start_time(benchmark: BaseIsaacBenchmark, value: float): +def log_simulation_start_time(benchmark: Any, value: float): + SingleMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.SingleMeasurement measurement = SingleMeasurement(name="Simulation Start Time", value=value, unit="ms") benchmark.store_custom_measurement("startup", measurement) -def log_total_start_time(benchmark: BaseIsaacBenchmark, value: float): +def log_total_start_time(benchmark: Any, value: float): + SingleMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.SingleMeasurement measurement = SingleMeasurement(name="Total Start Time (Launch to Train)", value=value, unit="ms") benchmark.store_custom_measurement("startup", measurement) -def log_runtime_step_times(benchmark: BaseIsaacBenchmark, value: dict, compute_stats=True): +def log_runtime_step_times(benchmark: Any, value: dict, compute_stats=True): + DictMeasurement = lazy.isaacsim.benchmark.services.metrics.measurements.DictMeasurement measurement = DictMeasurement(name="Step Frametimes", value=value) benchmark.store_custom_measurement("runtime", measurement) if compute_stats: log_min_max_mean_stats(benchmark, value) -def log_rl_policy_rewards(benchmark: BaseIsaacBenchmark, value: list): +def log_rl_policy_rewards(benchmark: Any, value: list): + metrics_mod = lazy.isaacsim.benchmark.services.metrics.measurements + ListMeasurement = metrics_mod.ListMeasurement + SingleMeasurement = metrics_mod.SingleMeasurement measurement = ListMeasurement(name="Rewards", value=value) benchmark.store_custom_measurement("train", measurement) # log max reward @@ -96,7 +103,10 @@ def log_rl_policy_rewards(benchmark: BaseIsaacBenchmark, value: list): benchmark.store_custom_measurement("train", measurement) -def log_rl_policy_episode_lengths(benchmark: BaseIsaacBenchmark, value: list): +def log_rl_policy_episode_lengths(benchmark: Any, value: list): + metrics_mod = lazy.isaacsim.benchmark.services.metrics.measurements + ListMeasurement = metrics_mod.ListMeasurement + SingleMeasurement = metrics_mod.SingleMeasurement measurement = ListMeasurement(name="Episode Lengths", value=value) benchmark.store_custom_measurement("train", measurement) # log max episode length diff --git a/scripts/demos/arms.py b/scripts/demos/arms.py index ac050d8fe65..36a1d335703 100644 --- a/scripts/demos/arms.py +++ b/scripts/demos/arms.py @@ -35,9 +35,8 @@ import numpy as np import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/scripts/demos/h1_locomotion.py b/scripts/demos/h1_locomotion.py index 4f1ed0aabfb..255e36df82f 100644 --- a/scripts/demos/h1_locomotion.py +++ b/scripts/demos/h1_locomotion.py @@ -45,13 +45,12 @@ import carb import omni -from isaacsim.core.utils.stage import get_current_stage -from omni.kit.viewport.utility import get_viewport_from_window_name -from omni.kit.viewport.utility.camera_state import ViewportCameraState from pxr import Gf, Sdf from rsl_rl.runners import OnPolicyRunner +from isaaclab import lazy from isaaclab.envs import ManagerBasedRLEnv +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.utils.math import quat_apply from isaaclab.utils.pretrained_checkpoint import get_published_pretrained_checkpoint @@ -112,7 +111,7 @@ def __init__(self): def create_camera(self): """Creates a camera to be used for third-person view.""" stage = get_current_stage() - self.viewport = get_viewport_from_window_name("Viewport") + self.viewport = lazy.omni_kit_viewport_utility.get_viewport_from_window_name("Viewport") # Create camera self.camera_path = "/World/Camera" self.perspective_path = "/OmniverseKit_Persp" @@ -200,7 +199,7 @@ def _update_camera(self): camera_pos = quat_apply(base_quat, self._camera_local_transform) + base_pos - camera_state = ViewportCameraState(self.camera_path, self.viewport) + camera_state = lazy.omni_kit_viewport_utility.camera_state.ViewportCameraState(self.camera_path, self.viewport) eye = Gf.Vec3d(camera_pos[0].item(), camera_pos[1].item(), camera_pos[2].item()) target = Gf.Vec3d(base_pos[0].item(), base_pos[1].item(), base_pos[2].item() + 0.6) camera_state.set_position_world(eye, True) diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index db5bddef23a..a87263ba81a 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -35,9 +35,8 @@ import numpy as np import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation ## diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index 9ebbbb66370..46454fea85c 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -37,7 +37,6 @@ import random -from isaacsim.core.utils.stage import get_current_stage from pxr import Gf, Sdf import isaaclab.sim as sim_utils @@ -52,6 +51,7 @@ ) from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sim import SimulationContext +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.utils import Timer, configclass from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR diff --git a/scripts/demos/quadrupeds.py b/scripts/demos/quadrupeds.py index f22dcb1f26f..1acd2b2c1cc 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -35,9 +35,8 @@ import numpy as np import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation ## diff --git a/scripts/environments/state_machine/lift_teddy_bear.py b/scripts/environments/state_machine/lift_teddy_bear.py index 5d6db415390..b9c55091f5c 100644 --- a/scripts/environments/state_machine/lift_teddy_bear.py +++ b/scripts/environments/state_machine/lift_teddy_bear.py @@ -19,6 +19,7 @@ import argparse +from isaaclab import lazy from isaaclab.app import AppLauncher # add argparse arguments @@ -34,9 +35,7 @@ simulation_app = app_launcher.app # disable metrics assembler due to scene graph instancing -from isaacsim.core.utils.extensions import disable_extension - -disable_extension("omni.usd.metrics.assembler.ui") +lazy.isaacsim.core.utils.extensions.disable_extension("omni.usd.metrics.assembler.ui") """Rest everything else.""" diff --git a/scripts/tools/check_instanceable.py b/scripts/tools/check_instanceable.py index a18c2207404..4418d0dbe8d 100644 --- a/scripts/tools/check_instanceable.py +++ b/scripts/tools/check_instanceable.py @@ -44,6 +44,7 @@ import contextlib import os +from isaaclab import lazy from isaaclab.app import AppLauncher # add argparse arguments @@ -64,12 +65,8 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.utils.carb import set_carb_setting -from isaacsim.core.utils.stage import get_current_stage - +import isaaclab.sim.utils.prims as prim_utils +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.utils import Timer from isaaclab.utils.assets import check_file_path @@ -80,7 +77,7 @@ def main(): if not check_file_path(args_cli.input): raise ValueError(f"Invalid file path: {args_cli.input}") # Load kit helper - sim = SimulationContext( + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( stage_units_in_meters=1.0, physics_dt=0.01, rendering_dt=0.01, backend="torch", device="cuda:0" ) @@ -96,10 +93,10 @@ def main(): sim.get_physics_context().set_gpu_total_aggregate_pairs_capacity(2**21) # enable hydra scene-graph instancing # this is needed to visualize the scene when fabric is enabled - set_carb_setting(sim._settings, "/persistent/omnihydra/useSceneGraphInstancing", True) + sim._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) # Create interface to clone the scene - cloner = GridCloner(spacing=args_cli.spacing, stage=stage) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=args_cli.spacing, stage=stage) cloner.define_base_env("/World/envs") prim_utils.define_prim("/World/envs/env_0") # Spawn things into stage diff --git a/scripts/tools/convert_mesh.py b/scripts/tools/convert_mesh.py index bce2c66ef71..7d9dc0b52c3 100644 --- a/scripts/tools/convert_mesh.py +++ b/scripts/tools/convert_mesh.py @@ -93,9 +93,9 @@ import os import carb -import isaacsim.core.utils.stage as stage_utils import omni.kit.app +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import MeshConverter, MeshConverterCfg from isaaclab.sim.schemas import schemas_cfg from isaaclab.utils.assets import check_file_path diff --git a/scripts/tools/convert_mjcf.py b/scripts/tools/convert_mjcf.py index 5b56bacaf0d..9b11736b523 100644 --- a/scripts/tools/convert_mjcf.py +++ b/scripts/tools/convert_mjcf.py @@ -63,9 +63,9 @@ import os import carb -import isaacsim.core.utils.stage as stage_utils import omni.kit.app +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import MjcfConverter, MjcfConverterCfg from isaaclab.utils.assets import check_file_path from isaaclab.utils.dict import print_dict diff --git a/scripts/tools/convert_urdf.py b/scripts/tools/convert_urdf.py index 767d61b0a21..5af2eaf69f5 100644 --- a/scripts/tools/convert_urdf.py +++ b/scripts/tools/convert_urdf.py @@ -81,9 +81,9 @@ import os import carb -import isaacsim.core.utils.stage as stage_utils import omni.kit.app +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg from isaaclab.utils.assets import check_file_path from isaaclab.utils.dict import print_dict diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index a544f5a470b..b4af407832f 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -31,9 +31,8 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/scripts/tutorials/01_assets/run_articulation.py b/scripts/tutorials/01_assets/run_articulation.py index 433825e1a3d..70ecdd35d50 100644 --- a/scripts/tutorials/01_assets/run_articulation.py +++ b/scripts/tutorials/01_assets/run_articulation.py @@ -34,9 +34,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation from isaaclab.sim import SimulationContext diff --git a/scripts/tutorials/01_assets/run_deformable_object.py b/scripts/tutorials/01_assets/run_deformable_object.py index a309a2c6926..b66fba4c92e 100644 --- a/scripts/tutorials/01_assets/run_deformable_object.py +++ b/scripts/tutorials/01_assets/run_deformable_object.py @@ -35,9 +35,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.utils.math as math_utils from isaaclab.assets import DeformableObject, DeformableObjectCfg from isaaclab.sim import SimulationContext diff --git a/scripts/tutorials/01_assets/run_rigid_object.py b/scripts/tutorials/01_assets/run_rigid_object.py index 03ff929f0ec..9d2ac625e09 100644 --- a/scripts/tutorials/01_assets/run_rigid_object.py +++ b/scripts/tutorials/01_assets/run_rigid_object.py @@ -35,9 +35,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.utils.math as math_utils from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.sim import SimulationContext diff --git a/scripts/tutorials/01_assets/run_surface_gripper.py b/scripts/tutorials/01_assets/run_surface_gripper.py index 6b8e32d2127..bc4e9e60ffd 100644 --- a/scripts/tutorials/01_assets/run_surface_gripper.py +++ b/scripts/tutorials/01_assets/run_surface_gripper.py @@ -35,9 +35,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation, SurfaceGripper, SurfaceGripperCfg from isaaclab.sim import SimulationContext diff --git a/scripts/tutorials/04_sensors/run_ray_caster.py b/scripts/tutorials/04_sensors/run_ray_caster.py index 484b523beb5..fe60b011c8f 100644 --- a/scripts/tutorials/04_sensors/run_ray_caster.py +++ b/scripts/tutorials/04_sensors/run_ray_caster.py @@ -33,9 +33,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.sensors.ray_caster import RayCaster, RayCasterCfg, patterns from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/scripts/tutorials/04_sensors/run_ray_caster_camera.py b/scripts/tutorials/04_sensors/run_ray_caster_camera.py index 77b3f2e6e0b..9be8e51c3af 100644 --- a/scripts/tutorials/04_sensors/run_ray_caster_camera.py +++ b/scripts/tutorials/04_sensors/run_ray_caster_camera.py @@ -38,10 +38,10 @@ import os import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sensors.ray_caster import RayCasterCamera, RayCasterCameraCfg, patterns from isaaclab.utils import convert_dict_to_backend from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/scripts/tutorials/04_sensors/run_usd_camera.py b/scripts/tutorials/04_sensors/run_usd_camera.py index f9ae93bb0e1..7341959646d 100644 --- a/scripts/tutorials/04_sensors/run_usd_camera.py +++ b/scripts/tutorials/04_sensors/run_usd_camera.py @@ -65,10 +65,10 @@ import random import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import RAY_CASTER_MARKER_CFG diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 48a598cd23f..5720239e19c 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.48.6" +version = "0.48.7" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 2e5a44188ce..4aa40ee902d 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +0.48.7 (2025-11-25) +~~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Changed import from ``isaacsim.core.utils.prims`` to ``isaaclab.sim.utils.prims`` to reduce IsaacLab dependencies. + + 0.48.6 (2025-11-18) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index 153bfa74bfd..daac2b2d15f 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -18,12 +18,12 @@ import re import signal import sys -from typing import Any, Literal +from typing import TYPE_CHECKING, Any, Literal -with contextlib.suppress(ModuleNotFoundError): - import isaacsim # noqa: F401 +from isaaclab import lazy -from isaacsim import SimulationApp +if TYPE_CHECKING: + from isaacsim import SimulationApp class ExplicitAction(argparse.Action): @@ -163,7 +163,7 @@ def __init__(self, launcher_args: argparse.Namespace | dict | None = None, **kwa """ @property - def app(self) -> SimulationApp: + def app(self) -> "SimulationApp": """The launched SimulationApp.""" if self._app is not None: return self._app @@ -698,7 +698,8 @@ def _resolve_experience_file(self, launcher_args: dict): self._sim_experience_file = launcher_args.pop("experience", "") # If nothing is provided resolve the experience file based on the headless flag - kit_app_exp_path = os.environ["EXP_PATH"] + kit_app_exp_path = os.environ.get("EXP_PATH", os.path.join(os.path.dirname(lazy.isaacsim.__file__), "apps")) + isaaclab_app_exp_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), *[".."] * 4, "apps") # For Isaac Sim 4.5 compatibility, we use the 4.5 app files in a different folder # if launcher_args.get("use_isaacsim_45", False): @@ -808,7 +809,7 @@ def _create_app(self): sys.argv = sys.argv[:idx] + sys.argv[idx + 1 :] # launch simulation app - self._app = SimulationApp(self._sim_app_config, experience=self._sim_experience_file) + self._app = lazy.isaacsim.SimulationApp(self._sim_app_config, experience=self._sim_experience_file) # enable sys stdout and stderr sys.stdout = sys.__stdout__ @@ -932,7 +933,7 @@ def _interrupt_signal_handle_callback(self, signal, frame): def is_isaac_sim_version_4_5(self) -> bool: if not hasattr(self, "_is_sim_ver_4_5"): # 1) Try to read the VERSION file (for manual / binary installs) - version_path = os.path.abspath(os.path.join(os.path.dirname(isaacsim.__file__), "../../VERSION")) + version_path = os.path.abspath(os.path.join(os.path.dirname(lazy.isaacsim.__file__), "../../VERSION")) if os.path.isfile(version_path): with open(version_path) as f: ver = f.readline().strip() @@ -982,13 +983,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 = lazy.isaacsim.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 + lazy.isaacsim.SimulationApp._start_app = _start_app_patch def __patch_pxr_gf_matrix4d(self, launcher_args: dict): import traceback diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation.py b/source/isaaclab/isaaclab/assets/articulation/articulation.py index a45a5e3054e..5ae2c199410 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation.py @@ -15,13 +15,12 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager -from isaacsim.core.version import get_version from pxr import PhysxSchema, UsdPhysics import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils import isaaclab.utils.string as string_utils +from isaaclab import lazy from isaaclab.actuators import ActuatorBase, ActuatorBaseCfg, ImplicitActuator from isaaclab.utils.types import ArticulationActions @@ -881,7 +880,7 @@ def write_joint_friction_coefficient_to_sim( physx_envs_ids_cpu = physx_env_ids.cpu() # set into simulation - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: self.root_physx_view.set_dof_friction_coefficients( self._data.joint_friction_coeff.cpu(), indices=physx_envs_ids_cpu ) @@ -909,7 +908,7 @@ def write_joint_dynamic_friction_coefficient_to_sim( joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None, ): - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning("Setting joint dynamic friction coefficients are not supported in Isaac Sim < 5.0") return # resolve indices @@ -935,7 +934,7 @@ def write_joint_viscous_friction_coefficient_to_sim( joint_ids: Sequence[int] | slice | None = None, env_ids: Sequence[int] | None = None, ): - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning("Setting joint viscous friction coefficients are not supported in Isaac Sim < 5.0") return # resolve indices @@ -1334,7 +1333,7 @@ def set_spatial_tendon_stiffness( spatial_tendon_ids: The tendon indices to set the stiffness for. Defaults to None (all spatial tendons). env_ids: The environment indices to set the stiffness for. Defaults to None (all environments). """ - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning( "Spatial tendons are not supported in Isaac Sim < 5.0. Please update to Isaac Sim 5.0 or later." ) @@ -1365,7 +1364,7 @@ def set_spatial_tendon_damping( spatial_tendon_ids: The tendon indices to set the damping for. Defaults to None (all spatial tendons). env_ids: The environment indices to set the damping for. Defaults to None (all environments). """ - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning( "Spatial tendons are not supported in Isaac Sim < 5.0. Please update to Isaac Sim 5.0 or later." ) @@ -1396,7 +1395,7 @@ def set_spatial_tendon_limit_stiffness( spatial_tendon_ids: The tendon indices to set the limit stiffness for. Defaults to None (all spatial tendons). env_ids: The environment indices to set the limit stiffness for. Defaults to None (all environments). """ - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning( "Spatial tendons are not supported in Isaac Sim < 5.0. Please update to Isaac Sim 5.0 or later." ) @@ -1427,7 +1426,7 @@ def set_spatial_tendon_offset( spatial_tendon_ids: The tendon indices to set the offset for. Defaults to None (all spatial tendons). env_ids: The environment indices to set the offset for. Defaults to None (all environments). """ - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning( "Spatial tendons are not supported in Isaac Sim < 5.0. Please update to Isaac Sim 5.0 or later." ) @@ -1475,7 +1474,7 @@ def write_spatial_tendon_properties_to_sim( def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.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. @@ -1520,7 +1519,7 @@ def _initialize_impl(self): if self._root_physx_view._backend is None: raise RuntimeError(f"Failed to create articulation at: {root_prim_path_expr}. Please check PhysX logs.") - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: logger.warning( "Spatial tendons are not supported in Isaac Sim < 5.0: patching spatial-tendon getter" " and setter to use dummy value" @@ -1582,7 +1581,7 @@ def _create_buffers(self): self._data.default_joint_stiffness = self.root_physx_view.get_dof_stiffnesses().to(self.device).clone() self._data.default_joint_damping = self.root_physx_view.get_dof_dampings().to(self.device).clone() self._data.default_joint_armature = self.root_physx_view.get_dof_armatures().to(self.device).clone() - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: self._data.default_joint_friction_coeff = ( self.root_physx_view.get_dof_friction_coefficients().to(self.device).clone() ) @@ -1744,7 +1743,7 @@ def _process_actuators_cfg(self): self.write_joint_velocity_limit_to_sim(actuator.velocity_limit_sim, joint_ids=actuator.joint_indices) self.write_joint_armature_to_sim(actuator.armature, joint_ids=actuator.joint_indices) self.write_joint_friction_coefficient_to_sim(actuator.friction, joint_ids=actuator.joint_indices) - if int(get_version()[2]) >= 5: + if int(lazy.isaacsim.core.version.get_version()[2]) >= 5: self.write_joint_dynamic_friction_coefficient_to_sim( actuator.dynamic_friction, joint_ids=actuator.joint_indices ) @@ -1758,7 +1757,7 @@ def _process_actuators_cfg(self): self._data.default_joint_damping[:, actuator.joint_indices] = actuator.damping self._data.default_joint_armature[:, actuator.joint_indices] = actuator.armature self._data.default_joint_friction_coeff[:, actuator.joint_indices] = actuator.friction - if int(get_version()[2]) >= 5: + if int(lazy.isaacsim.core.version.get_version()[2]) >= 5: self._data.default_joint_dynamic_friction_coeff[:, actuator.joint_indices] = actuator.dynamic_friction self._data.default_joint_viscous_friction_coeff[:, actuator.joint_indices] = actuator.viscous_friction @@ -1932,7 +1931,7 @@ def _log_articulation_info(self): dampings = self.root_physx_view.get_dof_dampings()[0].tolist() # -- properties armatures = self.root_physx_view.get_dof_armatures()[0].tolist() - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: static_frictions = self.root_physx_view.get_dof_friction_coefficients()[0].tolist() else: friction_props = self.root_physx_view.get_dof_friction_properties() @@ -1946,7 +1945,7 @@ def _log_articulation_info(self): # create table for term information joint_table = PrettyTable() joint_table.title = f"Simulation Joint Information (Prim path: {self.cfg.prim_path})" - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: joint_table.field_names = [ "Index", "Name", @@ -1978,7 +1977,7 @@ def _log_articulation_info(self): joint_table.align["Name"] = "l" # add info on each term for index, name in enumerate(self.joint_names): - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: joint_table.add_row([ index, name, diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation_data.py b/source/isaaclab/isaaclab/assets/articulation/articulation_data.py index 172a002a3a3..c0e2f99bb0e 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation_data.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation_data.py @@ -8,9 +8,9 @@ import weakref import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.utils.buffers import TimestampedBuffer # import logger @@ -53,7 +53,7 @@ def __init__(self, root_physx_view: physx.ArticulationView, device: str): self._sim_timestamp = 0.0 # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() gravity = self._physics_sim_view.get_gravity() # Convert to direction vector gravity_dir = torch.tensor((gravity[0], gravity[1], gravity[2]), device=self.device) diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index c2fb652e842..23540dcf0b6 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -14,12 +14,12 @@ from collections.abc import Sequence from typing import TYPE_CHECKING, Any -import isaacsim.core.utils.prims as prim_utils 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 import lazy from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: @@ -296,9 +296,9 @@ def safe_callback(callback_name, event, obj_ref): order=10, ) # register prim deletion callback - self._prim_deletion_callback_id = SimulationManager.register_callback( + self._prim_deletion_callback_id = lazy.isaacsim.core.simulation_manager.SimulationManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref), - event=IsaacEvents.PRIM_DELETION, + event=lazy.isaacsim.core.simulation_manager.IsaacEvents.PRIM_DELETION, ) def _initialize_callback(self, event): @@ -310,8 +310,8 @@ 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 = lazy.isaacsim.core.simulation_manager.SimulationManager.get_backend() + self._device = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_device() # initialize the asset try: self._initialize_impl() @@ -349,7 +349,7 @@ 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) + lazy.isaacsim.core.simulation_manager.SimulationManager.deregister_callback(self._prim_deletion_callback_id) self._prim_deletion_callback_id = None if self._initialize_handle: self._initialize_handle.unsubscribe() diff --git a/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py b/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py index a98a8f42f60..a977f5ed9be 100644 --- a/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py +++ b/source/isaaclab/isaaclab/assets/deformable_object/deformable_object.py @@ -11,11 +11,11 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager from pxr import PhysxSchema, UsdShade import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.markers import VisualizationMarkers from ..asset_base import AssetBase @@ -266,7 +266,7 @@ def transform_nodal_pos( def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() # obtain the first prim in the regex expression (all others are assumed to be a copy of this) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if template_prim is None: diff --git a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py index ee13c56ee19..48151500501 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py +++ b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object.py @@ -11,12 +11,12 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils import isaaclab.utils.string as string_utils +from isaaclab import lazy from ..asset_base import AssetBase from .rigid_object_data import RigidObjectData @@ -458,7 +458,7 @@ def set_external_force_and_torque( def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() # obtain the first prim in the regex expression (all others are assumed to be a copy of this) template_prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if template_prim is None: diff --git a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py index ff223d7c5bc..cc9d483c924 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py +++ b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection.py @@ -12,12 +12,12 @@ from typing import TYPE_CHECKING import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils import isaaclab.utils.string as string_utils +from isaaclab import lazy from ..asset_base import AssetBase from .rigid_object_collection_data import RigidObjectCollectionData @@ -592,7 +592,7 @@ def reshape_data_to_view(self, data: torch.Tensor) -> torch.Tensor: def _initialize_impl(self): # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() root_prim_path_exprs = [] for name, rigid_object_cfg in self.cfg.rigid_objects.items(): # obtain the first prim in the regex expression (all others are assumed to be a copy of this) diff --git a/source/isaaclab/isaaclab/assets/surface_gripper/surface_gripper.py b/source/isaaclab/isaaclab/assets/surface_gripper/surface_gripper.py index 0e510852f79..667d1297592 100644 --- a/source/isaaclab/isaaclab/assets/surface_gripper/surface_gripper.py +++ b/source/isaaclab/isaaclab/assets/surface_gripper/surface_gripper.py @@ -10,15 +10,14 @@ import warnings from typing import TYPE_CHECKING -from isaacsim.core.utils.extensions import enable_extension -from isaacsim.core.version import get_version - import isaaclab.sim as sim_utils +from isaaclab import lazy from isaaclab.assets import AssetBase if TYPE_CHECKING: - from isaacsim.robot.surface_gripper import GripperView + import isaacsim.robot.surface_gripper as _sg # type: ignore[import] + GripperView = _sg.GripperView # type: ignore[misc] from .surface_gripper_cfg import SurfaceGripperCfg # import logger @@ -58,7 +57,7 @@ def __init__(self, cfg: SurfaceGripperCfg): # copy the configuration self._cfg = cfg.copy() - isaac_sim_version = get_version() + isaac_sim_version = lazy.isaacsim.core.version.get_version() # checks for Isaac Sim v5.0 to ensure that the surface gripper is supported if int(isaac_sim_version[2]) < 5: raise Exception( @@ -254,8 +253,7 @@ def _initialize_impl(self) -> None: Use `--device cpu` to run the simulation on CPU. """ - enable_extension("isaacsim.robot.surface_gripper") - from isaacsim.robot.surface_gripper import GripperView + lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.robot.surface_gripper") # Check that we are using the CPU backend. if self._device != "cpu": @@ -307,7 +305,7 @@ def _initialize_impl(self) -> None: # Initialize gripper view and set properties. Note we do not set the properties through the gripper view # to avoid having to convert them to list of floats here. Instead, we do it in the update_gripper_properties # function which does this conversion internally. - self._gripper_view = GripperView( + self._gripper_view = lazy.isaacsim.robot.surface_gripper.GripperView( self._prim_expr, ) self.update_gripper_properties( diff --git a/source/isaaclab/isaaclab/controllers/config/rmp_flow.py b/source/isaaclab/isaaclab/controllers/config/rmp_flow.py index f3d214168fb..b1cd4303c0f 100644 --- a/source/isaaclab/isaaclab/controllers/config/rmp_flow.py +++ b/source/isaaclab/isaaclab/controllers/config/rmp_flow.py @@ -5,25 +5,28 @@ import os -from isaacsim.core.utils.extensions import get_extension_path_from_name - +from isaaclab import lazy from isaaclab.controllers.rmp_flow import RmpFlowControllerCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR ISAACLAB_NUCLEUS_RMPFLOW_DIR = os.path.join(ISAACLAB_NUCLEUS_DIR, "Controllers", "RmpFlowAssets") -# Note: RMP-Flow config files for supported robots are stored in the motion_generation extension -_RMP_CONFIG_DIR = os.path.join( - get_extension_path_from_name("isaacsim.robot_motion.motion_generation"), "motion_policy_configs" -) + +def _get_rmp_config_dir() -> str: + """Return the RMPFlow config directory from the motion_generation extension.""" + return os.path.join( + lazy.isaacsim.core.utils.extensions.get_extension_path_from_name("isaacsim.robot_motion.motion_generation"), + "motion_policy_configs", + ) + # Path to current directory _CUR_DIR = os.path.dirname(os.path.realpath(__file__)) FRANKA_RMPFLOW_CFG = RmpFlowControllerCfg( - config_file=os.path.join(_RMP_CONFIG_DIR, "franka", "rmpflow", "franka_rmpflow_common.yaml"), + config_file=os.path.join(_get_rmp_config_dir(), "franka", "rmpflow", "franka_rmpflow_common.yaml"), urdf_file=os.path.join(_CUR_DIR, "data", "lula_franka_gen.urdf"), - collision_file=os.path.join(_RMP_CONFIG_DIR, "franka", "rmpflow", "robot_descriptor.yaml"), + collision_file=os.path.join(_get_rmp_config_dir(), "franka", "rmpflow", "robot_descriptor.yaml"), frame_name="panda_end_effector", evaluations_per_frame=5, ) @@ -31,9 +34,9 @@ UR10_RMPFLOW_CFG = RmpFlowControllerCfg( - config_file=os.path.join(_RMP_CONFIG_DIR, "ur10", "rmpflow", "ur10_rmpflow_config.yaml"), - urdf_file=os.path.join(_RMP_CONFIG_DIR, "ur10", "ur10_robot.urdf"), - collision_file=os.path.join(_RMP_CONFIG_DIR, "ur10", "rmpflow", "ur10_robot_description.yaml"), + config_file=os.path.join(_get_rmp_config_dir(), "ur10", "rmpflow", "ur10_rmpflow_config.yaml"), + urdf_file=os.path.join(_get_rmp_config_dir(), "ur10", "ur10_robot.urdf"), + collision_file=os.path.join(_get_rmp_config_dir(), "ur10", "rmpflow", "ur10_robot_description.yaml"), frame_name="ee_link", evaluations_per_frame=5, ) diff --git a/source/isaaclab/isaaclab/controllers/rmp_flow.py b/source/isaaclab/isaaclab/controllers/rmp_flow.py index b9ce875c390..d6438d43cab 100644 --- a/source/isaaclab/isaaclab/controllers/rmp_flow.py +++ b/source/isaaclab/isaaclab/controllers/rmp_flow.py @@ -6,22 +6,16 @@ import torch from dataclasses import MISSING -import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.prims import SingleArticulation - -# enable motion generation extensions -from isaacsim.core.utils.extensions import enable_extension - -enable_extension("isaacsim.robot_motion.lula") -enable_extension("isaacsim.robot_motion.motion_generation") - -from isaacsim.robot_motion.motion_generation import ArticulationMotionPolicy -from isaacsim.robot_motion.motion_generation.lula.motion_policies import RmpFlow, RmpFlowSmoothed - +import isaaclab.sim.utils.prims as prim_utils +from isaaclab import lazy +from isaaclab.sim import SimulationContext from isaaclab.utils import configclass from isaaclab.utils.assets import retrieve_file_path +# enable motion generation extensions when this module is imported +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.robot_motion.lula") +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.robot_motion.motion_generation") + @configclass class RmpFlowControllerCfg: @@ -84,17 +78,18 @@ def initialize(self, prim_paths_expr: str): self._prim_paths = prim_utils.find_matching_prim_paths(prim_paths_expr) self.num_robots = len(self._prim_paths) # resolve controller + motion_gen_mod = lazy.isaacsim.robot_motion.motion_generation if self.cfg.name == "rmp_flow": - controller_cls = RmpFlow + controller_cls = motion_gen_mod.lula.motion_policies.RmpFlow elif self.cfg.name == "rmp_flow_smoothed": - controller_cls = RmpFlowSmoothed + controller_cls = motion_gen_mod.lula.motion_policies.RmpFlowSmoothed else: raise ValueError(f"Unsupported controller in Lula library: {self.cfg.name}") # create all franka robots references and their controllers self.articulation_policies = list() for prim_path in self._prim_paths: # add robot reference - robot = SingleArticulation(prim_path) + robot = lazy.isaacsim.core.prims.SingleArticulation(prim_path) robot.initialize() # download files if they are not local @@ -112,7 +107,7 @@ def initialize(self, prim_paths_expr: str): ignore_robot_state_updates=self.cfg.ignore_robot_state_updates, ) # wrap rmpflow to connect to the Franka robot articulation - articulation_policy = ArticulationMotionPolicy(robot, rmpflow, physics_dt) + articulation_policy = motion_gen_mod.ArticulationMotionPolicy(robot, rmpflow, physics_dt) self.articulation_policies.append(articulation_policy) # get number of active joints self.active_dof_names = self.articulation_policies[0].get_motion_policy().get_active_joints() @@ -149,7 +144,7 @@ def compute(self) -> tuple[torch.Tensor, torch.Tensor]: # compute control actions for i, policy in enumerate(self.articulation_policies): # enable type-hinting - policy: ArticulationMotionPolicy + policy: lazy.isaacsim.robot_motion.motion_generation.ArticulationMotionPolicy # set rmpflow target to be the current position of the target cube. policy.get_motion_policy().set_end_effector_target( target_position=command[i, 0:3], target_orientation=command[i, 3:7] diff --git a/source/isaaclab/isaaclab/controllers/utils.py b/source/isaaclab/isaaclab/controllers/utils.py index b1341f4b04f..b7bc0bf0dbc 100644 --- a/source/isaaclab/isaaclab/controllers/utils.py +++ b/source/isaaclab/isaaclab/controllers/utils.py @@ -12,9 +12,9 @@ import os import re -from isaacsim.core.utils.extensions import enable_extension +from isaaclab import lazy -enable_extension("isaacsim.asset.exporter.urdf") +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.asset.exporter.urdf") from nvidia.srl.from_usd.to_urdf import UsdToUrdf diff --git a/source/isaaclab/isaaclab/devices/openxr/manus_vive.py b/source/isaaclab/isaaclab/devices/openxr/manus_vive.py index ff696bb0d2f..30bee83e6ea 100644 --- a/source/isaaclab/isaaclab/devices/openxr/manus_vive.py +++ b/source/isaaclab/isaaclab/devices/openxr/manus_vive.py @@ -15,8 +15,8 @@ from dataclasses import dataclass import carb -from isaacsim.core.version import get_version +from isaaclab import lazy from isaaclab.devices.openxr.common import HAND_JOINT_NAMES from isaaclab.devices.retargeter_base import RetargeterBase @@ -29,8 +29,6 @@ with contextlib.suppress(ModuleNotFoundError): from omni.kit.xr.core import XRCore -from isaacsim.core.prims import SingleXFormPrim - from .manus_vive_utils import HAND_JOINT_MAP, ManusViveIntegration @@ -70,7 +68,7 @@ def __init__(self, cfg: ManusViveCfg, retargeters: list[RetargeterBase] | None = """ super().__init__(retargeters) # Enforce minimum Isaac Sim version (>= 5.1) - version_info = get_version() + version_info = lazy.isaacsim.core.version.get_version() major, minor = int(version_info[2]), int(version_info[3]) if (major < 5) or (major == 5 and minor < 1): raise RuntimeError(f"ManusVive requires Isaac Sim >= 5.1. Detected version {major}.{minor}. ") @@ -91,7 +89,9 @@ def __init__(self, cfg: ManusViveCfg, retargeters: list[RetargeterBase] | None = self._previous_joint_poses_right = {name: default_pose.copy() for name in HAND_JOINT_NAMES} self._previous_headpose = default_pose.copy() - xr_anchor = SingleXFormPrim("/XRAnchor", position=self._xr_cfg.anchor_pos, orientation=self._xr_cfg.anchor_rot) + xr_anchor = lazy.isaacsim.core.prims.SingleXFormPrim( + "/XRAnchor", position=self._xr_cfg.anchor_pos, orientation=self._xr_cfg.anchor_rot + ) carb.settings.get_settings().set_float("/persistent/xr/profile/ar/render/nearPlane", self._xr_cfg.near_plane) carb.settings.get_settings().set_string("/persistent/xr/profile/ar/anchorMode", "custom anchor") carb.settings.get_settings().set_string("/xrstage/profile/ar/customAnchor", xr_anchor.prim_path) diff --git a/source/isaaclab/isaaclab/devices/openxr/manus_vive_utils.py b/source/isaaclab/isaaclab/devices/openxr/manus_vive_utils.py index db22628dfaa..1557bb191e2 100644 --- a/source/isaaclab/isaaclab/devices/openxr/manus_vive_utils.py +++ b/source/isaaclab/isaaclab/devices/openxr/manus_vive_utils.py @@ -8,7 +8,7 @@ import numpy as np from time import time -from isaacsim.core.utils.extensions import enable_extension +from isaaclab import lazy # For testing purposes, we need to mock the XRCore XRCore, XRPoseValidityFlags = None, None @@ -61,10 +61,9 @@ class ManusViveIntegration: def __init__(self): - enable_extension("isaacsim.xr.input_devices") - from isaacsim.xr.input_devices.impl.manus_vive_integration import get_manus_vive_integration - - _manus_vive_integration = get_manus_vive_integration() + lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.xr.input_devices") + manus_mod = lazy.isaacsim.xr.input_devices.impl.manus_vive_integration + _manus_vive_integration = manus_mod.get_manus_vive_integration() self.manus = _manus_vive_integration.manus_tracker self.vive_tracker = _manus_vive_integration.vive_tracker self.device_status = _manus_vive_integration.device_status diff --git a/source/isaaclab/isaaclab/devices/openxr/openxr_device.py b/source/isaaclab/isaaclab/devices/openxr/openxr_device.py index e929d102a5e..2b56c9c046d 100644 --- a/source/isaaclab/isaaclab/devices/openxr/openxr_device.py +++ b/source/isaaclab/isaaclab/devices/openxr/openxr_device.py @@ -18,6 +18,7 @@ # import logger logger = logging.getLogger(__name__) +from isaaclab import lazy from isaaclab.devices.openxr.common import HAND_JOINT_NAMES from isaaclab.devices.retargeter_base import RetargeterBase @@ -33,8 +34,6 @@ with contextlib.suppress(ModuleNotFoundError): from omni.kit.xr.core import XRCore, XRPoseValidityFlags, XRCoreEventType -from isaacsim.core.prims import SingleXFormPrim - class OpenXRDevice(DeviceBase): """An OpenXR-powered device for teleoperation and interaction. @@ -103,7 +102,7 @@ def __init__( else: self._xr_anchor_headset_path = "/World/XRAnchor" - _ = SingleXFormPrim( + _ = lazy.isaacsim.core.prims.SingleXFormPrim( self._xr_anchor_headset_path, position=self._xr_cfg.anchor_pos, orientation=self._xr_cfg.anchor_rot ) diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env.py b/source/isaaclab/isaaclab/envs/direct_marl_env.py index a8ff287bca5..829c18a10cc 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env.py @@ -20,8 +20,8 @@ import omni.kit.app import omni.physx -from isaacsim.core.version import get_version +from isaaclab import lazy from isaaclab.managers import EventManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext @@ -63,7 +63,7 @@ class DirectMARLEnv(gym.Env): metadata: ClassVar[dict[str, Any]] = { "render_modes": [None, "human", "rgb_array"], - "isaac_sim_version": get_version(), + "isaac_sim_version": lazy.isaacsim.core.version.get_version(), } """Metadata for the environment.""" @@ -543,7 +543,7 @@ def close(self): del self.viewport_camera_controller # clear callbacks and instance - if float(".".join(get_version()[2])) >= 5: + if float(".".join(lazy.isaacsim.core.version.get_version()[2])) >= 5: if self.cfg.sim.create_stage_in_memory: # detach physx stage omni.physx.get_physx_simulation_interface().detach_stage() diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 77ae7dec09f..c4788de4ad4 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -21,9 +21,8 @@ import omni.kit.app import omni.physx -from isaacsim.core.simulation_manager import SimulationManager -from isaacsim.core.version import get_version +from isaaclab import lazy from isaaclab.managers import EventManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext @@ -70,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": lazy.isaacsim.core.version.get_version(), } """Metadata for the environment.""" @@ -323,7 +322,7 @@ def reset(self, seed: int | None = None, options: dict[str, Any] | None = None) self.sim.render() if self.cfg.wait_for_textures and self.sim.has_rtx_sensors(): - while SimulationManager.assets_loading(): + while lazy.isaacsim.core.simulation_manager.SimulationManager.assets_loading(): self.sim.render() # return observations @@ -512,7 +511,7 @@ def close(self): del self.viewport_camera_controller # clear callbacks and instance - if float(".".join(get_version()[2])) >= 5: + if float(".".join(lazy.isaacsim.core.version.get_version()[2])) >= 5: if self.cfg.sim.create_stage_in_memory: # detach physx stage omni.physx.get_physx_simulation_interface().detach_stage() diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index b3ca7f2c001..ee448133954 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -11,9 +11,8 @@ from typing import Any import omni.physx -from isaacsim.core.simulation_manager import SimulationManager -from isaacsim.core.version import get_version +from isaaclab import lazy from isaaclab.managers import ActionManager, EventManager, ObservationManager, RecorderManager from isaaclab.scene import InteractiveScene from isaaclab.sim import SimulationContext @@ -382,7 +381,7 @@ def reset( 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(): + while lazy.isaacsim.core.simulation_manager.SimulationManager.assets_loading(): self.sim.render() # return observations @@ -529,7 +528,7 @@ def close(self): del self.scene # clear callbacks and instance - if float(".".join(get_version()[2])) >= 5: + if float(".".join(lazy.isaacsim.core.version.get_version()[2])) >= 5: if self.cfg.sim.create_stage_in_memory: # detach physx stage omni.physx.get_physx_simulation_interface().detach_stage() diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index 861072dec0a..01e7f539fd1 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -13,8 +13,7 @@ from collections.abc import Sequence from typing import Any, ClassVar -from isaacsim.core.version import get_version - +from isaaclab import lazy from isaaclab.managers import CommandManager, CurriculumManager, RewardManager, TerminationManager from isaaclab.ui.widgets import ManagerLiveVisualizer @@ -57,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": lazy.isaacsim.core.version.get_version(), } """Metadata for the environment.""" diff --git a/source/isaaclab/isaaclab/envs/mdp/events.py b/source/isaaclab/isaaclab/envs/mdp/events.py index 7ea6d7b2e0a..b40c8c2567a 100644 --- a/source/isaaclab/isaaclab/envs/mdp/events.py +++ b/source/isaaclab/isaaclab/envs/mdp/events.py @@ -21,11 +21,11 @@ import carb import omni.physics.tensors.impl.api as physx -from isaacsim.core.utils.extensions import enable_extension from pxr import Gf, Sdf, UsdGeom, Vt import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.actuators import ImplicitActuator from isaaclab.assets import Articulation, DeformableObject, RigidObject from isaaclab.managers import EventTermCfg, ManagerTermBase, SceneEntityCfg @@ -1414,7 +1414,7 @@ def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv): ) # enable replicator extension if not already enabled - enable_extension("omni.replicator.core") + lazy.isaacsim.core.utils.extensions.enable_extension("omni.replicator.core") # we import the module here since we may not always need the replicator import omni.replicator.core as rep @@ -1575,7 +1575,7 @@ def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv): super().__init__(cfg, env) # enable replicator extension if not already enabled - enable_extension("omni.replicator.core") + lazy.isaacsim.core.utils.extensions.enable_extension("omni.replicator.core") # we import the module here since we may not always need the replicator import omni.replicator.core as rep diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 5df0ce00705..ed053960852 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -11,12 +11,12 @@ 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 PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics +from isaaclab import lazy from isaaclab.sim.utils.stage import get_current_stage from isaaclab.ui.widgets import ManagerLiveVisualizer @@ -115,7 +115,7 @@ def _build_sim_frame(self): width=omni.ui.Fraction(1), height=0, collapsed=False, - style=isaacsim.gui.components.ui_utils.get_style(), + style=lazy.isaacsim.gui.components.ui_utils.get_style(), horizontal_scrollbar_policy=omni.ui.ScrollBarPolicy.SCROLLBAR_AS_NEEDED, vertical_scrollbar_policy=omni.ui.ScrollBarPolicy.SCROLLBAR_ALWAYS_ON, ) @@ -132,7 +132,7 @@ def _build_sim_frame(self): "tooltip": "Select a rendering mode\n" + self.env.sim.RenderMode.__doc__, "on_clicked_fn": lambda value: self.env.sim.set_render_mode(self.env.sim.RenderMode[value]), } - self.ui_window_elements["render_dropdown"] = isaacsim.gui.components.ui_utils.dropdown_builder( + self.ui_window_elements["render_dropdown"] = lazy.isaacsim.gui.components.ui_utils.dropdown_builder( **render_mode_cfg ) @@ -145,7 +145,7 @@ def _build_sim_frame(self): "tooltip": "Record the animation of the scene. Only effective if fabric is disabled.", "on_clicked_fn": lambda value: self._toggle_recording_animation_fn(value), } - self.ui_window_elements["record_animation"] = isaacsim.gui.components.ui_utils.state_btn_builder( + self.ui_window_elements["record_animation"] = lazy.isaacsim.gui.components.ui_utils.state_btn_builder( **record_animate_cfg ) # disable the button if fabric is not enabled @@ -159,7 +159,7 @@ def _build_viewer_frame(self): width=omni.ui.Fraction(1), height=0, collapsed=False, - style=isaacsim.gui.components.ui_utils.get_style(), + style=lazy.isaacsim.gui.components.ui_utils.get_style(), horizontal_scrollbar_policy=omni.ui.ScrollBarPolicy.SCROLLBAR_AS_NEEDED, vertical_scrollbar_policy=omni.ui.ScrollBarPolicy.SCROLLBAR_ALWAYS_ON, ) @@ -177,7 +177,7 @@ def _build_viewer_frame(self): "max": self.env.num_envs, "tooltip": "The environment index to follow. Only effective if follow mode is not 'World'.", } - self.ui_window_elements["viewer_env_index"] = isaacsim.gui.components.ui_utils.int_builder( + self.ui_window_elements["viewer_env_index"] = lazy.isaacsim.gui.components.ui_utils.int_builder( **viewport_origin_cfg ) # create a number slider to move to environment origin @@ -192,19 +192,19 @@ def _build_viewer_frame(self): "tooltip": "Select the viewport camera following mode.", "on_clicked_fn": self._set_viewer_origin_type_fn, } - self.ui_window_elements["viewer_follow"] = isaacsim.gui.components.ui_utils.dropdown_builder( + self.ui_window_elements["viewer_follow"] = lazy.isaacsim.gui.components.ui_utils.dropdown_builder( **viewer_follow_cfg ) # add viewer default eye and lookat locations - self.ui_window_elements["viewer_eye"] = isaacsim.gui.components.ui_utils.xyz_builder( + self.ui_window_elements["viewer_eye"] = lazy.isaacsim.gui.components.ui_utils.xyz_builder( label="Camera Eye", tooltip="Modify the XYZ location of the viewer eye.", default_val=self.env.cfg.viewer.eye, step=0.1, on_value_changed_fn=[self._set_viewer_location_fn] * 3, ) - self.ui_window_elements["viewer_lookat"] = isaacsim.gui.components.ui_utils.xyz_builder( + self.ui_window_elements["viewer_lookat"] = lazy.isaacsim.gui.components.ui_utils.xyz_builder( label="Camera Target", tooltip="Modify the XYZ location of the viewer target.", default_val=self.env.cfg.viewer.lookat, @@ -226,7 +226,7 @@ def _build_debug_vis_frame(self): width=omni.ui.Fraction(1), height=0, collapsed=False, - style=isaacsim.gui.components.ui_utils.get_style(), + style=lazy.isaacsim.gui.components.ui_utils.get_style(), horizontal_scrollbar_policy=omni.ui.ScrollBarPolicy.SCROLLBAR_AS_NEEDED, vertical_scrollbar_policy=omni.ui.ScrollBarPolicy.SCROLLBAR_ALWAYS_ON, ) @@ -414,7 +414,7 @@ def _create_debug_vis_ui_element(self, name: str, elem: object): ) omni.ui.Label( name.replace("_", " ").title(), - width=isaacsim.gui.components.ui_utils.LABEL_WIDTH - 12, + width=lazy.isaacsim.gui.components.ui_utils.LABEL_WIDTH - 12, alignment=omni.ui.Alignment.LEFT_CENTER, tooltip=text, ) @@ -430,7 +430,7 @@ def _create_debug_vis_ui_element(self, name: str, elem: object): checked=is_checked, on_checked_fn=lambda value, e=weakref.proxy(elem): e.set_debug_vis(value), ) - isaacsim.gui.components.ui_utils.add_line_rect_flourish() + lazy.isaacsim.gui.components.ui_utils.add_line_rect_flourish() # Create a panel for the debug visualization if isinstance(elem, ManagerLiveVisualizer): diff --git a/source/isaaclab/isaaclab/lazy.py b/source/isaaclab/isaaclab/lazy.py new file mode 100644 index 00000000000..84e3410103b --- /dev/null +++ b/source/isaaclab/isaaclab/lazy.py @@ -0,0 +1,22 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from .utils.lazy_importer import LazyImporter + +# Lazily import heavy dependencies so importing ``isaaclab`` does not +# immediately import them. Currently only ``isaacsim`` is required. +isaacsim = LazyImporter("isaacsim") +isaacsim_core_utils_viewports = LazyImporter("isaacsim.core.utils.viewports") +omni = LazyImporter("omni") +omni_metrics_assembler_core = LazyImporter("omni.metrics.assembler.core") +omni_kit_viewport_utility = LazyImporter("omni.kit.viewport.utility") + +__all__ = [ + "isaacsim", + "isaacsim_core_utils_viewports", + "omni", + "omni_metrics_assembler_core", + "omni_kit_viewport_utility", +] diff --git a/source/isaaclab/isaaclab/markers/visualization_markers.py b/source/isaaclab/isaaclab/markers/visualization_markers.py index 4cd2a0c4db8..84c8567ead7 100644 --- a/source/isaaclab/isaaclab/markers/visualization_markers.py +++ b/source/isaaclab/isaaclab/markers/visualization_markers.py @@ -29,8 +29,8 @@ from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics, Vt import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.spawners import SpawnerCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.configclass import configclass from isaaclab.utils.math import convert_quat @@ -68,7 +68,7 @@ class VisualizationMarkers: The class parses the configuration to create different the marker prototypes into the stage. Each marker prototype prim is created as a child of the :class:`UsdGeom.PointInstancer` prim. The prim path for the marker prim is resolved using the key of the marker in the :attr:`VisualizationMarkersCfg.markers` - dictionary. The marker prototypes are created using the :meth:`isaacsim.core.utils.create_prim` + dictionary. The marker prototypes are created using the :meth:`isaaclab.sim.utils.prims.create_prim` function, and then instanced using :class:`UsdGeom.PointInstancer` prim to allow creating multiple instances of the marker prims. diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index fee14e40a08..2276d48217c 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -6,15 +6,13 @@ import logging import torch from collections.abc import Sequence -from typing import Any +from typing import TYPE_CHECKING, Any import carb -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import XFormPrim -from isaacsim.core.version import get_version from pxr import PhysxSchema import isaaclab.sim as sim_utils +from isaaclab import lazy from isaaclab.assets import ( Articulation, ArticulationCfg, @@ -35,6 +33,9 @@ from .interactive_scene_cfg import InteractiveSceneCfg +if TYPE_CHECKING: + from isaacsim.core.prims import XFormPrim + # import logger logger = logging.getLogger(__name__) @@ -134,7 +135,7 @@ 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 = lazy.isaacsim.core.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) # create source prim @@ -145,7 +146,7 @@ def __init__(self, cfg: InteractiveSceneCfg): # 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])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: # clone the env xform env_origins = self.cloner.clone( @@ -185,7 +186,7 @@ def __init__(self, cfg: InteractiveSceneCfg): # this is done to make scene initialization faster at play time if self.cfg.replicate_physics and self.cfg.num_envs > 1: # check version of Isaac Sim to determine whether clone_in_fabric is valid - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: self.cloner.replicate_physics( source_prim_path=self.env_prim_paths[0], @@ -230,7 +231,7 @@ def clone_environments(self, copy_from_source: bool = False): ) # check version of Isaac Sim to determine whether clone_in_fabric is valid - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: # clone the environment env_origins = self.cloner.clone( @@ -409,7 +410,7 @@ def surface_grippers(self) -> dict[str, SurfaceGripper]: return self._surface_grippers @property - def extras(self) -> dict[str, XFormPrim]: + def extras(self) -> dict[str, "XFormPrim"]: """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`_ @@ -782,7 +783,9 @@ def _add_entities_from_cfg(self): ) # store xform prim view corresponding to this asset # all prims in the scene are Xform prims (i.e. have a transform component) - self._extras[asset_name] = XFormPrim(asset_cfg.prim_path, reset_xform_properties=False) + self._extras[asset_name] = lazy.isaacsim.core.prims.XFormPrim( + asset_cfg.prim_path, reset_xform_properties=False + ) else: raise ValueError(f"Unknown asset config type for {asset_name}: {asset_cfg}") # store global collision paths diff --git a/source/isaaclab/isaaclab/sensors/camera/camera.py b/source/isaaclab/isaaclab/sensors/camera/camera.py index 041272e8695..da82c3bcaaa 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera.py @@ -16,13 +16,12 @@ 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 Sdf, UsdGeom import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.sensors as sensor_utils -from isaaclab.sim.utils import stage as stage_utils +from isaaclab import lazy from isaaclab.utils import to_camel_case from isaaclab.utils.array import convert_to_torch from isaaclab.utils.math import ( @@ -148,7 +147,7 @@ def __init__(self, cfg: CameraCfg): self._data = CameraData() # HACK: we need to disable instancing for semantic_segmentation and instance_segmentation_fast to work - isaac_sim_version = get_version() + isaac_sim_version = lazy.isaacsim.core.version.get_version() # checks for Isaac Sim v4.5 as this issue exists there if int(isaac_sim_version[2]) == 4 and int(isaac_sim_version[3]) == 5: if "semantic_segmentation" in self.cfg.data_types or "instance_segmentation_fast" in self.cfg.data_types: @@ -406,7 +405,7 @@ def _initialize_impl(self): # Initialize parent class super()._initialize_impl() # Create a view for the sensor - self._view = XFormPrim(self.cfg.prim_path, reset_xform_properties=False) + self._view = lazy.isaacsim.core.prims.XFormPrim(self.cfg.prim_path, reset_xform_properties=False) self._view.initialize() # Check that sizes are correct if self._view.count != self._num_envs: diff --git a/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py b/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py index 3e9982135c5..6a8ad33d2dc 100644 --- a/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py +++ b/source/isaaclab/isaaclab/sensors/camera/tiled_camera.py @@ -14,10 +14,9 @@ import carb import warp as wp -from isaacsim.core.prims import XFormPrim -from isaacsim.core.version import get_version from pxr import UsdGeom +from isaaclab import lazy from isaaclab.utils.warp.kernels import reshape_tiled_image from ..sensor_base import SensorBase @@ -84,7 +83,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. """ - isaac_sim_version = float(".".join(get_version()[2:4])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2:4])) if isaac_sim_version < 4.2: raise RuntimeError( f"TiledCamera is only available from Isaac Sim 4.2.0. Current version is {isaac_sim_version}. Please" @@ -158,7 +157,7 @@ def _initialize_impl(self): # Initialize parent class SensorBase._initialize_impl(self) # Create a view for the sensor - self._view = XFormPrim(self.cfg.prim_path, reset_xform_properties=False) + self._view = lazy.isaacsim.core.prims.XFormPrim(self.cfg.prim_path, reset_xform_properties=False) self._view.initialize() # Check that sizes are correct if self._view.count != self._num_envs: diff --git a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py index aed50d390f8..138a1d521cc 100644 --- a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py @@ -14,11 +14,11 @@ import carb import omni.physics.tensors.impl.api as physx -from isaacsim.core.simulation_manager import SimulationManager from pxr import PhysxSchema import isaaclab.sim as sim_utils import isaaclab.utils.string as string_utils +from isaaclab import lazy from isaaclab.markers import VisualizationMarkers from isaaclab.utils.math import convert_quat @@ -255,7 +255,7 @@ def compute_first_air(self, dt: float, abs_tol: float = 1.0e-8) -> torch.Tensor: def _initialize_impl(self): super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() # check that only rigid bodies are selected leaf_pattern = self.cfg.prim_path.rsplit("/", 1)[-1] template_prim_path = self._parent_prims[0].GetPath().pathString diff --git a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py index b6d2e766302..f0bc093f82b 100644 --- a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py +++ b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer.py @@ -11,11 +11,11 @@ from collections.abc import Sequence from typing import TYPE_CHECKING -from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils import isaaclab.utils.string as string_utils +from isaaclab import lazy from isaaclab.markers import VisualizationMarkers from isaaclab.utils.math import ( combine_frame_transforms, @@ -249,7 +249,7 @@ def _initialize_impl(self): body_names_regex = [tracked_prim_path.replace("env_0", "env_*") for tracked_prim_path in tracked_prim_paths] # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() # Create a prim view for all frames and initialize it # order of transforms coming out of view will be source frame followed by target frame(s) self._frame_physx_view = self._physics_sim_view.create_rigid_body_view(body_names_regex) diff --git a/source/isaaclab/isaaclab/sensors/imu/imu.py b/source/isaaclab/isaaclab/sensors/imu/imu.py index 74baec8997b..1ec9baed92c 100644 --- a/source/isaaclab/isaaclab/sensors/imu/imu.py +++ b/source/isaaclab/isaaclab/sensors/imu/imu.py @@ -9,13 +9,13 @@ from collections.abc import Sequence from typing import TYPE_CHECKING -from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdPhysics import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.markers import VisualizationMarkers -from isaaclab.sim.utils import stage as stage_utils from ..sensor_base import SensorBase from .imu_data import ImuData @@ -128,7 +128,7 @@ def _initialize_impl(self): # Initialize parent class super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() # check if the prim at path is a rigid prim prim = sim_utils.find_first_matching_prim(self.cfg.prim_path) if prim is None: diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py index 723d669d8a0..c38831bbb49 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py @@ -15,12 +15,11 @@ import omni import omni.physics.tensors.impl.api as physx import warp as wp -from isaacsim.core.prims import XFormPrim -from isaacsim.core.simulation_manager import SimulationManager from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.markers import VisualizationMarkers from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.utils.math import convert_quat, quat_apply, quat_apply_yaw @@ -135,7 +134,7 @@ def reset(self, env_ids: Sequence[int] | None = None): def _initialize_impl(self): super()._initialize_impl() # obtain global simulation view - self._physics_sim_view = SimulationManager.get_physics_sim_view() + self._physics_sim_view = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_view() # check if the prim at path is an articulated or rigid prim # we do this since for physics-based view classes we can access their data directly # otherwise we need to use the xform view class which is slower @@ -151,7 +150,7 @@ def _initialize_impl(self): self._view = self._physics_sim_view.create_rigid_body_view(self.cfg.prim_path.replace(".*", "*")) found_supported_prim_class = True else: - self._view = XFormPrim(self.cfg.prim_path, reset_xform_properties=False) + self._view = lazy.isaacsim.core.prims.XFormPrim(self.cfg.prim_path, reset_xform_properties=False) found_supported_prim_class = True logger.warning(f"The prim at path {prim.GetPath().pathString} is not a physics prim! Using XFormPrim.") # check if prim view class is found @@ -236,7 +235,7 @@ def _initialize_rays_impl(self): def _update_buffers_impl(self, env_ids: Sequence[int]): """Fills the buffers of the sensor data.""" # obtain the poses of the sensors - if isinstance(self._view, XFormPrim): + if isinstance(self._view, lazy.isaacsim.core.prims.XFormPrim): pos_w, quat_w = self._view.get_world_poses(env_ids) elif isinstance(self._view, physx.ArticulationView): pos_w, quat_w = self._view.get_root_transforms()[env_ids].split([3, 4], dim=-1) diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py index 49e7fd54522..e05a4ef070a 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera.py @@ -10,11 +10,11 @@ from typing import TYPE_CHECKING, ClassVar, Literal import omni.physics.tensors.impl.api as physx -from isaacsim.core.prims import XFormPrim +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.sensors.camera import CameraData -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.warp import raycast_mesh from .ray_caster import RayCaster @@ -400,7 +400,7 @@ def _compute_view_world_poses(self, env_ids: Sequence[int]) -> tuple[torch.Tenso """ # obtain the poses of the sensors # note: clone arg doesn't exist for xform prim view so we need to do this manually - if isinstance(self._view, XFormPrim): + if isinstance(self._view, lazy.isaacsim.core.prims.XFormPrim): if isinstance(env_ids, slice): # catch the case where env_ids is a slice env_ids = self._ALL_INDICES pos_w, quat_w = self._view.get_world_poses(env_ids) diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index eb1f6ffb8d4..57cc11113b5 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -22,9 +22,9 @@ import omni.kit.app import omni.timeline -from isaacsim.core.simulation_manager import IsaacEvents, SimulationManager import isaaclab.sim as sim_utils +from isaaclab import lazy from isaaclab.sim.utils.stage import get_current_stage if TYPE_CHECKING: @@ -285,9 +285,9 @@ def safe_callback(callback_name, event, obj_ref): order=10, ) # register prim deletion callback - self._prim_deletion_callback_id = SimulationManager.register_callback( + self._prim_deletion_callback_id = lazy.isaacsim.core.simulation_manager.SimulationManager.register_callback( lambda event, obj_ref=obj_ref: safe_callback("_on_prim_deletion", event, obj_ref), - event=IsaacEvents.PRIM_DELETION, + event=lazy.isaacsim.core.simulation_manager.IsaacEvents.PRIM_DELETION, ) def _initialize_callback(self, event): @@ -333,7 +333,7 @@ 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) + lazy.isaacsim.core.simulation_manager.SimulationManager.deregister_callback(self._prim_deletion_callback_id) self._prim_deletion_callback_id = None if self._initialize_handle: self._initialize_handle.unsubscribe() diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py index 30ea04c28df..eeb4e5604b0 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py @@ -10,9 +10,9 @@ import omni import omni.kit.commands import omni.usd -from isaacsim.core.utils.extensions import enable_extension from pxr import Gf, Tf, Usd, UsdGeom, UsdPhysics, UsdUtils +from isaaclab import lazy from isaaclab.sim.converters.asset_converter_base import AssetConverterBase from isaaclab.sim.converters.mesh_converter_cfg import MeshConverterCfg from isaaclab.sim.schemas import schemas @@ -218,7 +218,7 @@ async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool Returns: True if the conversion succeeds. """ - enable_extension("omni.kit.asset_converter") + lazy.isaacsim.core.utils.extensions.enable_extension("omni.kit.asset_converter") import omni.kit.asset_converter import omni.usd diff --git a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py index aa1e52be339..9c5ab95f6f4 100644 --- a/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mjcf_converter.py @@ -7,9 +7,9 @@ import os -import isaacsim import omni.kit.commands -import omni.usd + +from isaaclab import lazy from .asset_converter_base import AssetConverterBase from .mjcf_converter_cfg import MjcfConverterCfg @@ -65,7 +65,7 @@ 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) -> lazy.isaacsim.asset.importer.mjcf.ImportConfig: """Returns the import configuration for MJCF to USD conversion. Returns: diff --git a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py index 82cf55d5405..c29c402a868 100644 --- a/source/isaaclab/isaaclab/sim/converters/urdf_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/urdf_converter.py @@ -8,11 +8,10 @@ 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 isaaclab import lazy from .asset_converter_base import AssetConverterBase from .urdf_converter_cfg import UrdfConverterCfg @@ -48,10 +47,9 @@ def __init__(self, cfg: UrdfConverterCfg): """ 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") - from isaacsim.asset.importer.urdf._urdf import acquire_urdf_interface + lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.asset.importer.urdf") - self._urdf_interface = acquire_urdf_interface() + self._urdf_interface = lazy.isaacsim.asset.importer.urdf._urdf.acquire_urdf_interface() super().__init__(cfg=cfg) """ @@ -95,7 +93,7 @@ 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) -> any: """Create and fill URDF ImportConfig with desired settings Returns: @@ -144,8 +142,7 @@ def _update_joint_parameters(self): def _set_joints_drive_type(self): """Set the joint drive type for all joints in the URDF model.""" - from isaacsim.asset.importer.urdf._urdf import UrdfJointDriveType - + UrdfJointDriveType = lazy.isaacsim.asset.importer.urdf._urdf.UrdfJointDriveType drive_type_mapping = { "force": UrdfJointDriveType.JOINT_DRIVE_FORCE, "acceleration": UrdfJointDriveType.JOINT_DRIVE_ACCELERATION, @@ -169,8 +166,7 @@ def _set_joints_drive_type(self): def _set_joints_drive_target_type(self): """Set the joint drive target type for all joints in the URDF model.""" - from isaacsim.asset.importer.urdf._urdf import UrdfJointTargetType - + UrdfJointTargetType = lazy.isaacsim.asset.importer.urdf._urdf.UrdfJointTargetType target_type_mapping = { "none": UrdfJointTargetType.JOINT_DRIVE_NONE, "position": UrdfJointTargetType.JOINT_DRIVE_POSITION, @@ -276,8 +272,7 @@ def _set_joint_drive_stiffness(self, joint, stiffness: float): joint: The joint from the URDF robot model. stiffness: The stiffness value. """ - from isaacsim.asset.importer.urdf._urdf import UrdfJointType - + UrdfJointType = lazy.isaacsim.asset.importer.urdf._urdf.UrdfJointType if joint.type == UrdfJointType.JOINT_PRISMATIC: joint.drive.set_strength(stiffness) else: @@ -291,8 +286,7 @@ def _set_joint_drive_damping(self, joint, damping: float): joint: The joint from the URDF robot model. damping: The damping value. """ - from isaacsim.asset.importer.urdf._urdf import UrdfJointType - + UrdfJointType = lazy.isaacsim.asset.importer.urdf._urdf.UrdfJointType if joint.type == UrdfJointType.JOINT_PRISMATIC: joint.drive.set_damping(damping) else: @@ -305,7 +299,8 @@ def _set_joint_drive_gains_from_natural_frequency(self, joint): Args: joint: The joint from the URDF robot model. """ - from isaacsim.asset.importer.urdf._urdf import UrdfJointDriveType, UrdfJointTargetType + UrdfJointDriveType = lazy.isaacsim.asset.importer.urdf._urdf.UrdfJointDriveType + UrdfJointTargetType = lazy.isaacsim.asset.importer.urdf._urdf.UrdfJointTargetType strength = self._urdf_interface.compute_natural_stiffness( self._robot_model, diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index 07ee06819e6..af579dc096f 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -26,18 +26,17 @@ 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 pxr import Gf, PhysxSchema, Sdf, Usd, UsdPhysics +from isaaclab import lazy from isaaclab.sim.utils import stage as stage_utils from .simulation_cfg import SimulationCfg from .spawners import DomeLightCfg, GroundPlaneCfg from .utils import ColoredFormatter, RateLimitFilter, bind_physics_material +_SimulationContext = lazy.isaacsim.core.api.simulation_context.SimulationContext + class SimulationContext(_SimulationContext): """A class to control simulation-related events such as physics stepping and rendering. @@ -146,7 +145,7 @@ def __init__(self, cfg: SimulationCfg | None = 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 = lazy.isaacsim.core.version.get_version() # apply carb physics settings self._apply_physics_settings() @@ -192,13 +191,12 @@ def __init__(self, cfg: SimulationCfg | None = None): else: # note: need to import here in case the UI is not available (ex. headless mode) import omni.ui as ui - from omni.kit.viewport.utility import get_active_viewport # set default render mode # note: this can be changed by calling the `set_render_mode` function self.render_mode = self.RenderMode.FULL_RENDERING # acquire viewport context - self._viewport_context = get_active_viewport() + self._viewport_context = lazy.omni_kit_viewport_utility.get_active_viewport() self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] # acquire viewport window # TODO @mayank: Why not just use get_active_viewport_and_window() directly? @@ -211,10 +209,8 @@ def __init__(self, cfg: SimulationCfg | None = None): # check the case where we don't need to render the viewport # since render_viewport can only be False in headless mode, we only need to check for offscreen_render if not self._render_viewport and self._offscreen_render: - # disable the viewport if offscreen_render is enabled - from omni.kit.viewport.utility import get_active_viewport - get_active_viewport().updates_enabled = False + lazy.omni_kit_viewport_utility.get_active_viewport().updates_enabled = False # override enable scene querying if rendering is enabled # this is needed for some GUI features @@ -266,7 +262,7 @@ def __init__(self, cfg: SimulationCfg | None = None): # set simulation device # note: Although Isaac Sim sets the physics device in the init function, # it does a render call which gets the wrong device. - SimulationManager.set_physics_sim_device(self.cfg.device) + lazy.isaacsim.core.simulation_manager.SimulationManager.set_physics_sim_device(self.cfg.device) # obtain the parsed device # This device should be the same as "self.cfg.device". However, for cases, where users specify the device @@ -274,7 +270,7 @@ def __init__(self, cfg: SimulationCfg | None = None): # Note: Since we fix the device from the configuration and don't expect users to change it at runtime, # we can obtain the device once from the SimulationManager.get_physics_sim_device() function. # This reduces the overhead of calling the function. - self._physics_device = SimulationManager.get_physics_sim_device() + self._physics_device = lazy.isaacsim.core.simulation_manager.SimulationManager.get_physics_sim_device() # create a simulation context to control the simulator if float(".".join(self._isaacsim_version[2])) < 5: @@ -390,7 +386,7 @@ def set_camera_view( """ # 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) + lazy.isaacsim_core_utils_viewports.set_camera_view(eye, target, camera_prim_path) def set_render_mode(self, mode: RenderMode): """Change the current render mode of the simulation. 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 79b5e5a0031..2cc48b4e4ae 100644 --- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py +++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files.py @@ -8,10 +8,11 @@ import logging from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils import omni.kit.commands from pxr import Gf, Sdf, Usd +import isaaclab.sim.utils.prims as prim_utils + # from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated try: import Semantics @@ -160,7 +161,7 @@ def spawn_ground_plane( # Apply physics material to ground plane collision_prim_path = prim_utils.get_prim_path( prim_utils.get_first_matching_child_prim( - prim_path, predicate=lambda x: prim_utils.get_prim_type_name(x) == "Plane" + prim_path, predicate=lambda x: prim_utils.from_prim_get_type_name(x) == "Plane" ) ) bind_physics_material(collision_prim_path, f"{prim_path}/physicsMaterial") diff --git a/source/isaaclab/isaaclab/sim/spawners/lights/lights.py b/source/isaaclab/isaaclab/sim/spawners/lights/lights.py index dccd00f4bca..119cdcbd116 100644 --- a/source/isaaclab/isaaclab/sim/spawners/lights/lights.py +++ b/source/isaaclab/isaaclab/sim/spawners/lights/lights.py @@ -7,9 +7,9 @@ from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils from pxr import Usd, UsdLux +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim.utils import clone, safe_set_attribute_on_usd_prim if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py index 966efec76b8..13f90cfb4b1 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py @@ -31,7 +31,7 @@ Usage: .. code-block:: python - import isaacsim.core.utils.prims as prim_utils + import isaaclab.sim.utils.prims as prim_utils import isaaclab.sim as sim_utils diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py index 293c81f0000..b404cb73970 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials.py @@ -7,9 +7,9 @@ from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils from pxr import PhysxSchema, Usd, UsdPhysics, UsdShade +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim.utils import clone, safe_set_attribute_on_usd_schema from isaaclab.sim.utils.stage import get_current_stage diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py index 30cd153a79c..aad404ebfe3 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials.py @@ -8,10 +8,10 @@ import logging from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils import omni.kit.commands from pxr import Usd +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim.utils import attach_stage_to_usd_context, clone, safe_set_attribute_on_usd_prim from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR diff --git a/source/isaaclab/isaaclab/sim/spawners/meshes/meshes.py b/source/isaaclab/isaaclab/sim/spawners/meshes/meshes.py index 17c23202ed6..a5b2a064e31 100644 --- a/source/isaaclab/isaaclab/sim/spawners/meshes/meshes.py +++ b/source/isaaclab/isaaclab/sim/spawners/meshes/meshes.py @@ -10,9 +10,9 @@ import trimesh.transformations from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils from pxr import Usd, UsdPhysics +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim import schemas from isaaclab.sim.utils import bind_physics_material, bind_visual_material, clone diff --git a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py index 3dccde74f6e..375aca23e00 100644 --- a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py +++ b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors.py @@ -8,12 +8,11 @@ import logging from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils import omni.kit.commands from pxr import Sdf, Usd -from isaaclab.sim.utils import clone -from isaaclab.sim.utils.stage import attach_stage_to_usd_context +import isaaclab.sim.utils.prims as prim_utils +from isaaclab.sim.utils import attach_stage_to_usd_context, clone from isaaclab.utils import to_camel_case if TYPE_CHECKING: diff --git a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py index f4fa156704a..0a045bf7534 100644 --- a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py +++ b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py @@ -7,9 +7,9 @@ from typing import TYPE_CHECKING -import isaacsim.core.utils.prims as prim_utils from pxr import Usd +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim import schemas from isaaclab.sim.utils import bind_physics_material, bind_visual_material, clone diff --git a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py index 4b0e75c0315..fb4082d1c66 100644 --- a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py +++ b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers.py @@ -10,12 +10,12 @@ from typing import TYPE_CHECKING import carb -import isaacsim.core.utils.prims as prim_utils from pxr import Sdf, 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 import stage as stage_utils if TYPE_CHECKING: from . import wrappers_cfg diff --git a/source/isaaclab/isaaclab/sim/utils/__init__.py b/source/isaaclab/isaaclab/sim/utils/__init__.py index 9d1dcbd0e33..a03ed9180ec 100644 --- a/source/isaaclab/isaaclab/sim/utils/__init__.py +++ b/source/isaaclab/isaaclab/sim/utils/__init__.py @@ -3,4 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause -from .utils import * # noqa: F401, F403 +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/logger.py b/source/isaaclab/isaaclab/sim/utils/logger.py new file mode 100644 index 00000000000..37764ebefa3 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/utils/logger.py @@ -0,0 +1,50 @@ +# 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 with logging utilities.""" + +from __future__ import annotations + +import logging +import time + +# import logger +logger = logging.getLogger(__name__) + + +# --- Colored formatter --- +class ColoredFormatter(logging.Formatter): + COLORS = { + "WARNING": "\033[33m", # orange/yellow + "ERROR": "\033[31m", # red + "CRITICAL": "\033[31m", # red + "INFO": "\033[0m", # reset + "DEBUG": "\033[0m", + } + RESET = "\033[0m" + + def format(self, record): + color = self.COLORS.get(record.levelname, self.RESET) + message = super().format(record) + return f"{color}{message}{self.RESET}" + + +# --- Custom rate-limited warning filter --- +class RateLimitFilter(logging.Filter): + def __init__(self, interval_seconds=5): + super().__init__() + self.interval = interval_seconds + self.last_emitted = {} + + def filter(self, record): + """Allow WARNINGs only once every few seconds per message.""" + if record.levelno != logging.WARNING: + return True + now = time.time() + msg_key = record.getMessage() + if msg_key not in self.last_emitted or (now - self.last_emitted[msg_key]) > self.interval: + self.last_emitted[msg_key] = now + return True + return False diff --git a/source/isaaclab/isaaclab/sim/utils/utils.py b/source/isaaclab/isaaclab/sim/utils/prims.py similarity index 63% rename from source/isaaclab/isaaclab/sim/utils/utils.py rename to source/isaaclab/isaaclab/sim/utils/prims.py index 7bef3ff9cf9..9f1473347ea 100644 --- a/source/isaaclab/isaaclab/sim/utils/utils.py +++ b/source/isaaclab/isaaclab/sim/utils/prims.py @@ -3,695 +3,1007 @@ # # SPDX-License-Identifier: BSD-3-Clause -"""Sub-module with USD-related utilities.""" - from __future__ import annotations import functools import inspect import logging +import numpy as np import re -import time -from collections.abc import Callable +from collections.abc import Callable, Sequence from typing import TYPE_CHECKING, Any import omni import omni.kit.commands -from isaacsim.core.cloner import Cloner -from isaacsim.core.version import get_version +import omni.usd +import usdrt from pxr import PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics, UsdShade +from isaaclab import lazy +from isaaclab.utils.string import to_camel_case + +from .semantics import add_labels +from .stage import add_reference_to_stage, attach_stage_to_usd_context, 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 -from isaaclab.sim import schemas -from isaaclab.utils.string import to_camel_case +# import logger +logger = logging.getLogger(__name__) -from .stage import attach_stage_to_usd_context, get_current_stage -if TYPE_CHECKING: - from isaaclab.sim.spawners.spawner_cfg import SpawnerCfg +SDF_type_to_Gf = { + "matrix3d": "Gf.Matrix3d", + "matrix3f": "Gf.Matrix3f", + "matrix4d": "Gf.Matrix4d", + "matrix4f": "Gf.Matrix4f", + "range1d": "Gf.Range1d", + "range1f": "Gf.Range1f", + "range2d": "Gf.Range2d", + "range2f": "Gf.Range2f", + "range3d": "Gf.Range3d", + "range3f": "Gf.Range3f", + "rect2i": "Gf.Rect2i", + "vec2d": "Gf.Vec2d", + "vec2f": "Gf.Vec2f", + "vec2h": "Gf.Vec2h", + "vec2i": "Gf.Vec2i", + "vec3d": "Gf.Vec3d", + "double3": "Gf.Vec3d", + "vec3f": "Gf.Vec3f", + "vec3h": "Gf.Vec3h", + "vec3i": "Gf.Vec3i", + "vec4d": "Gf.Vec4d", + "vec4f": "Gf.Vec4f", + "vec4h": "Gf.Vec4h", + "vec4i": "Gf.Vec4i", +} -# import logger -logger = logging.getLogger(__name__) """ -Attribute - Setters. +General Utils """ -def safe_set_attribute_on_usd_schema(schema_api: Usd.APISchemaBase, name: str, value: Any, camel_case: bool): - """Set the value of an attribute on its USD schema if it exists. +def create_prim( + prim_path: str, + prim_type: str = "Xform", + position: Sequence[float] | None = None, + translation: Sequence[float] | None = None, + orientation: Sequence[float] | None = None, + scale: Sequence[float] | None = None, + usd_path: str | None = None, + semantic_label: str | None = None, + semantic_type: str = "class", + attributes: dict | None = None, +) -> Usd.Prim: + """Create a prim into current USD stage. - A USD API schema serves as an interface or API for authoring and extracting a set of attributes. - They typically derive from the :class:`pxr.Usd.SchemaBase` class. This function checks if the - attribute exists on the schema and sets the value of the attribute if it exists. + The method applies specified transforms, the semantic label and set specified attributes. Args: - schema_api: The USD schema to set the attribute on. - name: The name of the attribute. - value: The value to set the attribute to. - camel_case: Whether to convert the attribute name to camel case. + prim_path: The path of the new prim. + prim_type: Prim type name + position: prim position (applied last) + translation: prim translation (applied last) + orientation: prim rotation as quaternion + scale: scaling factor in x, y, z. + usd_path: Path to the USD that this prim will reference. + semantic_label: Semantic label. + semantic_type: set to "class" unless otherwise specified. + attributes: Key-value pairs of prim attributes to set. Raises: - TypeError: When the input attribute name does not exist on the provided schema API. + Exception: If there is already a prim at the prim_path + + Returns: + The created USD prim. + + Example: + + .. code-block:: python + + >>> import numpy as np + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # create a cube (/World/Cube) of size 2 centered at (1.0, 0.5, 0.0) + >>> prims_utils.create_prim( + ... prim_path="/World/Cube", + ... prim_type="Cube", + ... position=np.array([1.0, 0.5, 0.0]), + ... attributes={"size": 2.0} + ... ) + Usd.Prim() + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # load an USD file (franka.usd) to the stage under the path /World/panda + >>> prims_utils.create_prim( + ... prim_path="/World/panda", + ... prim_type="Xform", + ... usd_path="/home//Documents/Assets/Robots/FrankaRobotics/FrankaPanda/franka.usd" + ... ) + Usd.Prim() """ - # if value is None, do nothing - if value is None: - return - # convert attribute name to camel case - if camel_case: - attr_name = to_camel_case(name, to="CC") - else: - attr_name = name - # retrieve the attribute - # reference: https://openusd.org/dev/api/_usd__page__common_idioms.html#Usd_Create_Or_Get_Property - attr = getattr(schema_api, f"Create{attr_name}Attr", None) - # check if attribute exists - if attr is not None: - attr().Set(value) + # 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: + return None + # apply attributes into prim + if attributes is not None: + for k, v in attributes.items(): + prim.GetAttribute(k).Set(v) + # 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 + 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: - # think: do we ever need to create the attribute if it doesn't exist? - # currently, we are not doing this since the schemas are already created with some defaults. - logger.error(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.") - raise TypeError(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.") + 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) + return prim -def safe_set_attribute_on_usd_prim(prim: Usd.Prim, attr_name: str, value: Any, camel_case: bool): - """Set the value of a attribute on its USD prim. - The function creates a new attribute if it does not exist on the prim. This is because in some cases (such - as with shaders), their attributes are not exposed as USD prim properties that can be altered. This function - allows us to set the value of the attributes in these cases. +def delete_prim(prim_path: str) -> None: + """Remove the USD Prim and its descendants from the scene if able Args: - prim: The USD prim to set the attribute on. - attr_name: The name of the attribute. - value: The value to set the attribute to. - camel_case: Whether to convert the attribute name to camel case. + prim_path: path of the prim in the stage + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.delete_prim("/World/Cube") """ - # if value is None, do nothing - if value is None: - return - # convert attribute name to camel case - if camel_case: - attr_name = to_camel_case(attr_name, to="cC") - # resolve sdf type based on value - if isinstance(value, bool): - sdf_type = Sdf.ValueTypeNames.Bool - elif isinstance(value, int): - sdf_type = Sdf.ValueTypeNames.Int - elif isinstance(value, float): - sdf_type = Sdf.ValueTypeNames.Float - elif isinstance(value, (tuple, list)) and len(value) == 3 and any(isinstance(v, float) for v in value): - sdf_type = Sdf.ValueTypeNames.Float3 - elif isinstance(value, (tuple, list)) and len(value) == 2 and any(isinstance(v, float) for v in value): - sdf_type = Sdf.ValueTypeNames.Float2 + omni.usd.commands.DeletePrimsCommand([prim_path]).do() + + +def get_prim_at_path(prim_path: str, fabric: bool = False) -> Usd.Prim | usdrt.Usd._Usd.Prim: + """Get the USD or Fabric Prim at a given path string + + Args: + prim_path: path of the prim in the stage. + fabric: True for fabric stage and False for USD stage. Defaults to False. + + Returns: + USD or Fabric Prim object at the given path in the current stage. + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.get_prim_at_path("/World/Cube") + Usd.Prim() + """ + + current_stage = get_current_stage(fabric=fabric) + if current_stage: + return current_stage.GetPrimAtPath(prim_path) else: - raise NotImplementedError( - f"Cannot set attribute '{attr_name}' with value '{value}'. Please modify the code to support this type." - ) + return None - # 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) - # change property - omni.kit.commands.execute( - "ChangePropertyCommand", - prop_path=Sdf.Path(f"{prim.GetPath()}.{attr_name}"), - value=value, - prev=None, - type_to_create_if_not_exist=sdf_type, - usd_context_name=prim.GetStage(), - ) +def get_prim_path(prim: Usd.Prim) -> str: + """Get the path of a given USD prim. + Args: + prim: The input USD prim. -""" -Decorators. -""" + Returns: + The path to the input prim. + Example: -def apply_nested(func: Callable) -> Callable: - """Decorator to apply a function to all prims under a specified prim-path. + .. code-block:: python - The function iterates over the provided prim path and all its children to apply input function - to all prims under the specified prim path. + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prim = prims_utils.get_prim_at_path("/World/Cube") # Usd.Prim() + >>> prims_utils.get_prim_path(prim) + /World/Cube + """ + if prim: + if isinstance(prim, Usd.Prim): + return prim.GetPath().pathString + else: + return prim.GetPath() - If the function succeeds to apply to a prim, it will not look at the children of that prim. - This is based on the physics behavior that nested schemas are not allowed. For example, a parent prim - and its child prim cannot both have a rigid-body schema applied on them, or it is not possible to - have nested articulations. - While traversing the prims under the specified prim path, the function will throw a warning if it - does not succeed to apply the function to any prim. This is because the user may have intended to - apply the function to a prim that does not have valid attributes, or the prim may be an instanced prim. +def is_prim_path_valid(prim_path: str, fabric: bool = False) -> bool: + """Check if a path has a valid USD Prim at it Args: - func: The function to apply to all prims under a specified prim-path. The function - must take the prim-path and other arguments. It should return a boolean indicating whether - the function succeeded or not. + prim_path: path of the prim in the stage + fabric: True for fabric stage and False for USD stage. Defaults to False. Returns: - The wrapped function that applies the function to all prims under a specified prim-path. + bool: True if the path points to a valid prim + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # given the stage: /World/Cube + >>> prims_utils.is_prim_path_valid("/World/Cube") + True + >>> prims_utils.is_prim_path_valid("/World/Cube/") + False + >>> prims_utils.is_prim_path_valid("/World/Sphere") # it doesn't exist + False + """ + prim = get_prim_at_path(prim_path, fabric=fabric) + if prim: + return prim.IsValid() + else: + return False + + +def define_prim(prim_path: str, prim_type: str = "Xform", fabric: bool = False) -> Usd.Prim: + """Create a USD Prim at the given prim_path of type prim_type unless one already exists + + .. note:: + + This method will create a prim of the specified type in the specified path. + To apply a transformation (position, orientation, scale), set attributes or + load an USD file while creating the prim use the ``create_prim`` function. + + Args: + prim_path: path of the prim in the stage + prim_type: The type of the prim to create. Defaults to "Xform". + fabric: True for fabric stage and False for USD stage. Defaults to False. Raises: - ValueError: If the prim-path does not exist on the stage. + Exception: If there is already a prim at the prim_path + + Returns: + The created USD prim. + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.define_prim("/World/Shapes", prim_type="Xform") + Usd.Prim() """ + if is_prim_path_valid(prim_path, fabric=fabric): + raise Exception(f"A prim already exists at prim path: {prim_path}") + return get_current_stage(fabric=fabric).DefinePrim(prim_path, prim_type) - @functools.wraps(func) - def wrapper(prim_path: str | Sdf.Path, *args, **kwargs): - # map args and kwargs to function signature so we can get the stage - # note: we do this to check if stage is given in arg or kwarg - sig = inspect.signature(func) - bound_args = sig.bind(prim_path, *args, **kwargs) - # get current stage - stage = bound_args.arguments.get("stage") - if stage is None: - stage = get_current_stage() - # get USD prim - prim: Usd.Prim = stage.GetPrimAtPath(prim_path) - # check if prim is valid - if not prim.IsValid(): - raise ValueError(f"Prim at path '{prim_path}' is not valid.") - # add iterable to check if property was applied on any of the prims - count_success = 0 - instanced_prim_paths = [] - # iterate over all prims under prim-path - all_prims = [prim] - while len(all_prims) > 0: - # get current prim - child_prim = all_prims.pop(0) - child_prim_path = child_prim.GetPath().pathString # type: ignore - # check if prim is a prototype - if child_prim.IsInstance(): - instanced_prim_paths.append(child_prim_path) - continue - # set properties - success = func(child_prim_path, *args, **kwargs) - # if successful, do not look at children - # this is based on the physics behavior that nested schemas are not allowed - if not success: - all_prims += child_prim.GetChildren() - else: - count_success += 1 - # check if we were successful in applying the function to any prim - if count_success == 0: - logger.warning( - f"Could not perform '{func.__name__}' on any prims under: '{prim_path}'." - " This might be because of the following reasons:" - "\n\t(1) The desired attribute does not exist on any of the prims." - "\n\t(2) The desired attribute exists on an instanced prim." - f"\n\t\tDiscovered list of instanced prim paths: {instanced_prim_paths}" - ) +def get_prim_type_name(prim_path: str | Usd.Prim, fabric: bool = False) -> str: + """Get the TypeName of the USD Prim at the path if it is valid - return wrapper + Args: + prim_path: path of the prim in the stage or the prim it self + fabric: True for fabric stage and False for USD stage. Defaults to False. + Raises: + Exception: If there is not a valid prim at the given path -def clone(func: Callable) -> Callable: - """Decorator for cloning a prim based on matching prim paths of the prim's parent. + Returns: + The TypeName of the USD Prim at the path string - The decorator checks if the parent prim path matches any prim paths in the stage. If so, it clones the - spawned prim at each matching prim path. For example, if the input prim path is: ``/World/Table_[0-9]/Bottle``, - the decorator will clone the prim at each matching prim path of the parent prim: ``/World/Table_0/Bottle``, - ``/World/Table_1/Bottle``, etc. - Note: - For matching prim paths, the decorator assumes that valid prims exist for all matching prim paths. - In case no matching prim paths are found, the decorator raises a ``RuntimeError``. + .. deprecated:: v3.0.0 + The `get_prim_type_name` attribute is deprecated. please use from_prim_path_get_type_name or + from_prim_get_type_name. + """ + logger.warning( + "get_prim_type_name is deprecated. Use from_prim_path_get_type_name or from_prim_get_type_name instead." + ) + if isinstance(prim_path, Usd.Prim): + return from_prim_get_type_name(prim=prim_path, fabric=fabric) + else: + return from_prim_path_get_type_name(prim_path=prim_path, fabric=fabric) + + +def from_prim_path_get_type_name(prim_path: str, fabric: bool = False) -> str: + """Get the TypeName of the USD Prim at the path if it is valid Args: - func: The function to decorate. + prim_path: path of the prim in the stage + fabric: True for fabric stage and False for USD stage. Defaults to False. Returns: - The decorated function that spawns the prim and clones it at each matching prim path. - It returns the spawned source prim, i.e., the first prim in the list of matching prim paths. + The TypeName of the USD Prim at the path string """ + if not is_prim_path_valid(prim_path, fabric=fabric): + raise Exception(f"A prim does not exist at prim path: {prim_path}") + prim = get_prim_at_path(prim_path, fabric=fabric) + if fabric: + return prim.GetTypeName() + else: + return prim.GetPrimTypeInfo().GetTypeName() - @functools.wraps(func) - def wrapper(prim_path: str | Sdf.Path, cfg: SpawnerCfg, *args, **kwargs): - # get stage handle - stage = get_current_stage() - # cast prim_path to str type in case its an Sdf.Path - prim_path = str(prim_path) - # check prim path is global - if not prim_path.startswith("/"): - raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") - # 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 +def from_prim_get_type_name(prim: Usd.Prim, fabric: bool = False) -> str: + """Get the TypeName of the USD Prim at the path if it is valid - # resolve matching prims for source prim path expression - if is_regex_expression and root_path != "": - source_prim_paths = 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] + Args: + prim: the valid usd.Prim + fabric: True for fabric stage and False for USD stage. Defaults to False. - # resolve prim paths for spawning and cloning - prim_paths = [f"{source_prim_path}/{asset_path}" for source_prim_path in source_prim_paths] - # spawn single instance - prim = func(prim_paths[0], cfg, *args, **kwargs) - # set the prim visibility - if hasattr(cfg, "visible"): - imageable = UsdGeom.Imageable(prim) - if cfg.visible: - imageable.MakeVisible() - else: - 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 - 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) - # activate rigid body contact sensors - if hasattr(cfg, "activate_contact_sensors") and cfg.activate_contact_sensors: - schemas.activate_contact_sensors(prim_paths[0]) - # 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, - ) - # return the source prim - return prim + Returns: + The TypeName of the USD Prim at the path string + """ + if fabric: + return prim.GetTypeName() + else: + return prim.GetPrimTypeInfo().GetTypeName() - return wrapper + +def move_prim(path_from: str, path_to: str) -> None: + """Run the Move command to change a prims USD Path in the stage + + Args: + path_from: Path of the USD Prim you wish to move + path_to: Final destination of the prim + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # given the stage: /World/Cube. Move the prim Cube outside the prim World + >>> prims_utils.move_prim("/World/Cube", "/Cube") + """ + omni.usd.commands.MovePrimCommand(path_from=path_from, path_to=path_to).do() """ -Material bindings. +USD Stage traversal. """ -@apply_nested -def bind_visual_material( +def get_first_matching_child_prim( prim_path: str | Sdf.Path, - material_path: str | Sdf.Path, + predicate: Callable[[Usd.Prim], bool], stage: Usd.Stage | None = None, - stronger_than_descendants: bool = True, -): - """Bind a visual material to a prim. + traverse_instance_prims: bool = True, +) -> Usd.Prim | None: + """Recursively get the first USD Prim at the path string that passes the predicate function. - This function is a wrapper around the USD command `BindMaterialCommand`_. + This function performs a depth-first traversal of the prim hierarchy starting from + :attr:`prim_path`, returning the first prim that satisfies the provided :attr:`predicate`. + It optionally supports traversal through instance prims, which are normally skipped in standard USD + traversals. - .. note:: - The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path - and all its descendants. + USD instance prims are lightweight copies of prototype scene structures and are not included + in default traversals unless explicitly handled. This function allows traversing into instances + when :attr:`traverse_instance_prims` is set to :attr:`True`. - .. _BindMaterialCommand: https://docs.omniverse.nvidia.com/kit/docs/omni.usd/latest/omni.usd.commands/omni.usd.commands.BindMaterialCommand.html + .. versionchanged:: 2.3.0 + + Added :attr:`traverse_instance_prims` to control whether to traverse instance prims. + By default, instance prims are now traversed. Args: - prim_path: The prim path where to apply the material. - material_path: The prim path of the material to apply. - stage: The stage where the prim and material exist. - Defaults to None, in which case the current stage is used. - stronger_than_descendants: Whether the material should override the material of its descendants. - Defaults to True. + prim_path: The path of the prim in the stage. + predicate: The function to test the prims against. It takes a prim as input and returns a boolean. + stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. + traverse_instance_prims: Whether to traverse instance prims. Defaults to True. + + Returns: + The first prim on the path that passes the predicate. If no prim passes the predicate, it returns None. Raises: - ValueError: If the provided prim paths do not exist on stage. + ValueError: If the prim path is not global (i.e: does not start with '/'). """ # get stage handle if stage is None: stage = get_current_stage() - # check if prim and material exists - if not stage.GetPrimAtPath(prim_path).IsValid(): - raise ValueError(f"Target prim '{material_path}' does not exist.") - if not stage.GetPrimAtPath(material_path).IsValid(): - raise ValueError(f"Visual material '{material_path}' does not exist.") - - # resolve token for weaker than descendants - if stronger_than_descendants: - binding_strength = "strongerThanDescendants" - else: - binding_strength = "weakerThanDescendants" - # obtain material binding API - # note: we prefer using the command here as it is more robust than the USD API - success, _ = omni.kit.commands.execute( - "BindMaterialCommand", - prim_path=prim_path, - material_path=material_path, - strength=binding_strength, - stage=stage, - ) - # return success - return success + # make paths str type if they aren't already + prim_path = str(prim_path) + # check if prim path is global + if not prim_path.startswith("/"): + raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") + # get prim + prim = stage.GetPrimAtPath(prim_path) + # check if prim is valid + if not prim.IsValid(): + raise ValueError(f"Prim at path '{prim_path}' is not valid.") + # iterate over all prims under prim-path + all_prims = [prim] + while len(all_prims) > 0: + # get current prim + child_prim = all_prims.pop(0) + # check if prim passes predicate + if predicate(child_prim): + return child_prim + # add children to list + if traverse_instance_prims: + all_prims += child_prim.GetFilteredChildren(Usd.TraverseInstanceProxies()) + else: + all_prims += child_prim.GetChildren() + return None -@apply_nested -def bind_physics_material( +def get_all_matching_child_prims( prim_path: str | Sdf.Path, - material_path: str | Sdf.Path, + predicate: Callable[[Usd.Prim], bool] = lambda _: True, + depth: int | None = None, stage: Usd.Stage | None = None, - stronger_than_descendants: bool = True, -): - """Bind a physics material to a prim. + traverse_instance_prims: bool = True, +) -> list[Usd.Prim]: + """Performs a search starting from the root and returns all the prims matching the predicate. - `Physics material`_ can be applied only to a prim with physics-enabled on them. This includes having - collision APIs, or deformable body APIs, or being a particle system. In case the prim does not have - any of these APIs, the function will not apply the material and return False. + This function performs a depth-first traversal of the prim hierarchy starting from + :attr:`prim_path`, returning all prims that satisfy the provided :attr:`predicate`. It optionally + supports traversal through instance prims, which are normally skipped in standard USD traversals. - .. note:: - The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path - and all its descendants. + USD instance prims are lightweight copies of prototype scene structures and are not included + in default traversals unless explicitly handled. This function allows traversing into instances + when :attr:`traverse_instance_prims` is set to :attr:`True`. - .. _Physics material: https://isaac-sim.github.io/IsaacLab/main/source/api/lab/isaaclab.sim.html#isaaclab.sim.SimulationCfg.physics_material + .. versionchanged:: 2.3.0 + + Added :attr:`traverse_instance_prims` to control whether to traverse instance prims. + By default, instance prims are now traversed. Args: - prim_path: The prim path where to apply the material. - material_path: The prim path of the material to apply. - stage: The stage where the prim and material exist. - Defaults to None, in which case the current stage is used. - stronger_than_descendants: Whether the material should override the material of its descendants. - Defaults to True. + prim_path: The root prim path to start the search from. + predicate: The predicate that checks if the prim matches the desired criteria. It takes a prim as input + and returns a boolean. Defaults to a function that always returns True. + depth: The maximum depth for traversal, should be bigger than zero if specified. + Defaults to None (i.e: traversal happens till the end of the tree). + stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. + traverse_instance_prims: Whether to traverse instance prims. Defaults to True. + + Returns: + A list containing all the prims matching the predicate. Raises: - ValueError: If the provided prim paths do not exist on stage. + ValueError: If the prim path is not global (i.e: does not start with '/'). """ # get stage handle if stage is None: stage = get_current_stage() - # check if prim and material exists - if not stage.GetPrimAtPath(prim_path).IsValid(): - raise ValueError(f"Target prim '{material_path}' does not exist.") - if not stage.GetPrimAtPath(material_path).IsValid(): - raise ValueError(f"Physics material '{material_path}' does not exist.") - # get USD prim + # make paths str type if they aren't already + prim_path = str(prim_path) + # check if prim path is global + if not prim_path.startswith("/"): + raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") + # get prim prim = stage.GetPrimAtPath(prim_path) - # check if prim has collision applied on it - has_physics_scene_api = prim.HasAPI(PhysxSchema.PhysxSceneAPI) - has_collider = prim.HasAPI(UsdPhysics.CollisionAPI) - has_deformable_body = prim.HasAPI(PhysxSchema.PhysxDeformableBodyAPI) - has_particle_system = prim.IsA(PhysxSchema.PhysxParticleSystem) - if not (has_physics_scene_api or has_collider or has_deformable_body or has_particle_system): - logger.debug( - f"Cannot apply physics material '{material_path}' on prim '{prim_path}'. It is neither a" - " PhysX scene, collider, a deformable body, nor a particle system." - ) - return False + # check if prim is valid + if not prim.IsValid(): + raise ValueError(f"Prim at path '{prim_path}' is not valid.") + # check if depth is valid + if depth is not None and depth <= 0: + raise ValueError(f"Depth must be bigger than zero, got {depth}.") - # obtain material binding API - if prim.HasAPI(UsdShade.MaterialBindingAPI): - material_binding_api = UsdShade.MaterialBindingAPI(prim) - else: - material_binding_api = UsdShade.MaterialBindingAPI.Apply(prim) - # obtain the material prim + # iterate over all prims under prim-path + # list of tuples (prim, current_depth) + all_prims_queue = [(prim, 0)] + output_prims = [] + while len(all_prims_queue) > 0: + # get current prim + child_prim, current_depth = all_prims_queue.pop(0) + # check if prim passes predicate + if predicate(child_prim): + output_prims.append(child_prim) + # add children to list + if depth is None or current_depth < depth: + # resolve prims under the current prim + if traverse_instance_prims: + children = child_prim.GetFilteredChildren(Usd.TraverseInstanceProxies()) + else: + children = child_prim.GetChildren() + # add children to list + all_prims_queue += [(child, current_depth + 1) for child in children] - material = UsdShade.Material(stage.GetPrimAtPath(material_path)) - # resolve token for weaker than descendants - if stronger_than_descendants: - binding_strength = UsdShade.Tokens.strongerThanDescendants - else: - binding_strength = UsdShade.Tokens.weakerThanDescendants - # apply the material - material_binding_api.Bind(material, bindingStrength=binding_strength, materialPurpose="physics") # type: ignore - # return success - return True + return output_prims -""" -Exporting. -""" - - -def export_prim_to_file( - path: str | Sdf.Path, - source_prim_path: str | Sdf.Path, - target_prim_path: str | Sdf.Path | None = None, - stage: Usd.Stage | None = None, -): - """Exports a prim from a given stage to a USD file. - - The function creates a new layer at the provided path and copies the prim to the layer. - It sets the copied prim as the default prim in the target layer. Additionally, it updates - the stage up-axis and meters-per-unit to match the current stage. +def find_first_matching_prim(prim_path_regex: str, stage: Usd.Stage | None = None) -> Usd.Prim | None: + """Find the first matching prim in the stage based on input regex expression. Args: - path: The filepath path to export the prim to. - source_prim_path: The prim path to export. - target_prim_path: The prim path to set as the default prim in the target layer. - Defaults to None, in which case the source prim path is used. - stage: The stage where the prim exists. Defaults to None, in which case the - current stage is used. + prim_path_regex: The regex expression for prim path. + stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. + + Returns: + The first prim that matches input expression. If no prim matches, returns None. Raises: - ValueError: If the prim paths are not global (i.e: do not start with '/'). + ValueError: If the prim path is not global (i.e: does not start with '/'). """ # get stage handle if stage is None: stage = get_current_stage() - # automatically casting to str in case args - # are path types - path = str(path) - source_prim_path = str(source_prim_path) - if target_prim_path is not None: - target_prim_path = str(target_prim_path) + # check prim path is global + if not prim_path_regex.startswith("/"): + raise ValueError(f"Prim path '{prim_path_regex}' is not global. It must start with '/'.") + prim_path_regex = _normalize_legacy_wildcard_pattern(prim_path_regex) + # need to wrap the token patterns in '^' and '$' to prevent matching anywhere in the string + pattern = f"^{prim_path_regex}$" + compiled_pattern = re.compile(pattern) + # obtain matching prim (depth-first search) + for prim in stage.Traverse(): + # check if prim passes predicate + if compiled_pattern.match(prim.GetPath().pathString) is not None: + return prim + return None - if not source_prim_path.startswith("/"): - raise ValueError(f"Source prim path '{source_prim_path}' is not global. It must start with '/'.") - if target_prim_path is not None and not target_prim_path.startswith("/"): - raise ValueError(f"Target prim path '{target_prim_path}' is not global. It must start with '/'.") - # get root layer - source_layer = stage.GetRootLayer() +def _normalize_legacy_wildcard_pattern(prim_path_regex: str) -> str: + """Convert legacy '*' wildcard usage to '.*' and warn users.""" + fixed_regex = re.sub(r"(? list[Usd.Prim]: + """Find all the matching prims in the stage based on input regex expression. - # specify the prim to copy - source_prim_path = Sdf.Path(source_prim_path) - if target_prim_path is None: - target_prim_path = source_prim_path + Args: + prim_path_regex: The regex expression for prim path. + stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. - # copy the prim - Sdf.CreatePrimInLayer(target_layer, target_prim_path) - Sdf.CopySpec(source_layer, source_prim_path, target_layer, target_prim_path) - # set the default prim - target_layer.defaultPrim = Sdf.Path(target_prim_path).name - # resolve all paths relative to layer path - omni.usd.resolve_paths(source_layer.identifier, target_layer.identifier) - # save the stage - target_layer.Save() + Returns: + A list of prims that match input expression. + Raises: + ValueError: If the prim path is not global (i.e: does not start with '/'). + """ + prim_path_regex = _normalize_legacy_wildcard_pattern(prim_path_regex) + # get stage handle + if stage is None: + stage = get_current_stage() -""" -USD Prim properties. -""" + # check prim path is global + if not prim_path_regex.startswith("/"): + raise ValueError(f"Prim path '{prim_path_regex}' is not global. It must start with '/'.") + # need to wrap the token patterns in '^' and '$' to prevent matching anywhere in the string + tokens = prim_path_regex.split("/")[1:] + tokens = [f"^{token}$" for token in tokens] + # iterate over all prims in stage (breath-first search) + all_prims = [stage.GetPseudoRoot()] + output_prims = [] + for index, token in enumerate(tokens): + token_compiled = re.compile(token) + for prim in all_prims: + for child in prim.GetAllChildren(): + if token_compiled.match(child.GetName()) is not None: + output_prims.append(child) + if index < len(tokens) - 1: + all_prims = output_prims + output_prims = [] + return output_prims -def make_uninstanceable(prim_path: str | Sdf.Path, stage: Usd.Stage | None = None): - """Check if a prim and its descendants are instanced and make them uninstanceable. +def find_matching_prim_paths(prim_path_regex: str, stage: Usd.Stage | None = None) -> list[str]: + """Find all the matching prim paths in the stage based on input regex expression. - This function checks if the prim at the specified prim path and its descendants are instanced. - If so, it makes the respective prim uninstanceable by disabling instancing on the prim. + Args: + prim_path_regex: The regex expression for prim path. + stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. - This is useful when we want to modify the properties of a prim that is instanced. For example, if we - want to apply a different material on an instanced prim, we need to make the prim uninstanceable first. + Returns: + A list of prim paths that match input expression. + + Raises: + ValueError: If the prim path is not global (i.e: does not start with '/'). + """ + # obtain matching prims + output_prims = find_matching_prims(prim_path_regex, stage) + # convert prims to prim paths + output_prim_paths = [] + for prim in output_prims: + output_prim_paths.append(prim.GetPath().pathString) + return output_prim_paths + + +def find_global_fixed_joint_prim( + prim_path: str | Sdf.Path, check_enabled_only: bool = False, stage: Usd.Stage | None = None +) -> UsdPhysics.Joint | None: + """Find the fixed joint prim under the specified prim path that connects the target to the simulation world. + + A joint is a connection between two bodies. A fixed joint is a joint that does not allow relative motion + between the two bodies. When a fixed joint has only one target body, it is considered to attach the body + to the simulation world. + + This function finds the fixed joint prim that has only one target under the specified prim path. If no such + fixed joint prim exists, it returns None. Args: - prim_path: The prim path to check. + prim_path: The prim path to search for the fixed joint prim. + check_enabled_only: Whether to consider only enabled fixed joints. Defaults to False. + If False, then all joints (enabled or disabled) are considered. stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. + Returns: + The fixed joint prim that has only one target. If no such fixed joint prim exists, it returns None. + Raises: ValueError: If the prim path is not global (i.e: does not start with '/'). + ValueError: If the prim path does not exist on the stage. """ # get stage handle if stage is None: stage = get_current_stage() - # make paths str type if they aren't already - prim_path = str(prim_path) - # check if prim path is global + # check prim path is global if not prim_path.startswith("/"): raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") - # get prim - prim: Usd.Prim = stage.GetPrimAtPath(prim_path) - # check if prim is valid + + # check if prim exists + prim = stage.GetPrimAtPath(prim_path) if not prim.IsValid(): raise ValueError(f"Prim at path '{prim_path}' is not valid.") - # iterate over all prims under prim-path - all_prims = [prim] - while len(all_prims) > 0: - # get current prim - child_prim = all_prims.pop(0) - # check if prim is instanced - if child_prim.IsInstance(): - # make the prim uninstanceable - child_prim.SetInstanceable(False) - # add children to list - all_prims += child_prim.GetFilteredChildren(Usd.TraverseInstanceProxies()) + fixed_joint_prim = None + # we check all joints under the root prim and classify the asset as fixed base if there exists + # a fixed joint that has only one target (i.e. the root link). + for prim in Usd.PrimRange(prim): + # note: ideally checking if it is FixedJoint would have been enough, but some assets use "Joint" as the + # schema name which makes it difficult to distinguish between the two. + joint_prim = UsdPhysics.Joint(prim) + if joint_prim: + # if check_enabled_only is True, we only consider enabled joints + if check_enabled_only and not joint_prim.GetJointEnabledAttr().Get(): + continue + # check body 0 and body 1 exist + body_0_exist = joint_prim.GetBody0Rel().GetTargets() != [] + body_1_exist = joint_prim.GetBody1Rel().GetTargets() != [] + # if either body 0 or body 1 does not exist, we have a fixed joint that connects to the world + if not (body_0_exist and body_1_exist): + fixed_joint_prim = joint_prim + break -def resolve_prim_pose( - prim: Usd.Prim, ref_prim: Usd.Prim | None = None -) -> tuple[tuple[float, float, float], tuple[float, float, float, float]]: - """Resolve the pose of a prim with respect to another prim. + return fixed_joint_prim - Note: - This function ignores scale and skew by orthonormalizing the transformation - matrix at the final step. However, if any ancestor prim in the hierarchy - has non-uniform scale, that scale will still affect the resulting position - and orientation of the prim (because it's baked into the transform before - scale removal). - In other words: scale **is not removed hierarchically**. If you need - completely scale-free poses, you must walk the transform chain and strip - scale at each level. Please open an issue if you need this functionality. +def get_articulation_root_api_prim_path(prim_path): + """Get the prim path that has the Articulation Root API + + .. note:: + + This function assumes that all prims defined by a regular expression correspond to the same articulation type Args: - prim: The USD prim to resolve the pose for. - ref_prim: The USD prim to compute the pose with respect to. - Defaults to None, in which case the world frame is used. + prim_path: path or regex of the prim(s) on which to search for the prim containing the API Returns: - A tuple containing the position (as a 3D vector) and the quaternion orientation - in the (w, x, y, z) format. + path or regex of the prim(s) that has the Articulation Root API. + If no prim has been found, the same input value is returned - Raises: - ValueError: If the prim or ref prim is not valid. - """ - # check if prim is valid - if not prim.IsValid(): - raise ValueError(f"Prim at path '{prim.GetPath().pathString}' is not valid.") - # get prim xform - xform = UsdGeom.Xformable(prim) - prim_tf = xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) - # sanitize quaternion - # this is needed, otherwise the quaternion might be non-normalized - prim_tf = prim_tf.GetOrthonormalized() + Example: - if ref_prim is not None: - # check if ref prim is valid - if not ref_prim.IsValid(): - raise ValueError(f"Ref prim at path '{ref_prim.GetPath().pathString}' is not valid.") - # get ref prim xform - ref_xform = UsdGeom.Xformable(ref_prim) - ref_tf = ref_xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) - # make sure ref tf is orthonormal - ref_tf = ref_tf.GetOrthonormalized() - # compute relative transform to get prim in ref frame - prim_tf = prim_tf * ref_tf.GetInverse() + .. code-block:: python - # extract position and orientation - prim_pos = [*prim_tf.ExtractTranslation()] - prim_quat = [prim_tf.ExtractRotationQuat().real, *prim_tf.ExtractRotationQuat().imaginary] - return tuple(prim_pos), tuple(prim_quat) + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # given the stage: /World/env/Ant, /World/env_01/Ant, /World/env_02/Ant + >>> # search specifying the prim with the Articulation Root API + >>> prims_utils.get_articulation_root_api_prim_path("/World/env/Ant/torso") + /World/env/Ant/torso + >>> # search specifying some ancestor prim that does not have the Articulation Root API + >>> prims_utils.get_articulation_root_api_prim_path("/World/env/Ant") + /World/env/Ant/torso + >>> # regular expression search + >>> prims_utils.get_articulation_root_api_prim_path("/World/env.*/Ant") + /World/env.*/Ant/torso + """ + predicate = lambda path: get_prim_at_path(path).HasAPI(UsdPhysics.ArticulationRootAPI) # noqa: E731 + # single prim + if Sdf.Path.IsValidPathString(prim_path) and is_prim_path_valid(prim_path): + prim = get_first_matching_child_prim(prim_path, predicate) + if prim is not None: + return get_prim_path(prim) + # regular expression + else: + paths = find_matching_prim_paths(prim_path) + if len(paths): + prim = get_first_matching_child_prim(paths[0], predicate) + if prim is not None: + path = get_prim_path(prim) + remainder_path = "/".join(path.split("/")[prim_path.count("/") + 1 :]) + if remainder_path != "": + return prim_path + "/" + remainder_path + else: + return prim_path + return prim_path -def resolve_prim_scale(prim: Usd.Prim) -> tuple[float, float, float]: - """Resolve the scale of a prim in the world frame. +""" +Prim Attribute Queries +""" - At an attribute level, a USD prim's scale is a scaling transformation applied to the prim with - respect to its parent prim. This function resolves the scale of the prim in the world frame, - by computing the local to world transform of the prim. This is equivalent to traversing up - the prim hierarchy and accounting for the rotations and scales of the prims. - For instance, if a prim has a scale of (1, 2, 3) and it is a child of a prim with a scale of (4, 5, 6), - then the scale of the prim in the world frame is (4, 10, 18). +def is_prim_ancestral(prim_path: str) -> bool: + """Check if any of the prims ancestors were brought in as a reference Args: - prim: The USD prim to resolve the scale for. + prim_path: The path to the USD prim. Returns: - The scale of the prim in the x, y, and z directions in the world frame. + True if prim is part of a referenced prim, false otherwise. - Raises: - ValueError: If the prim is not valid. + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # /World/Cube is a prim created + >>> prims_utils.is_prim_ancestral("/World/Cube") + False + >>> # /World/panda is an USD file loaded (as reference) under that path + >>> prims_utils.is_prim_ancestral("/World/panda") + False + >>> prims_utils.is_prim_ancestral("/World/panda/panda_link0") + True """ - # check if prim is valid - if not prim.IsValid(): - raise ValueError(f"Prim at path '{prim.GetPath().pathString}' is not valid.") - # compute local to world transform - xform = UsdGeom.Xformable(prim) - world_transform = xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) - # extract scale - return tuple([*(v.GetLength() for v in world_transform.ExtractRotationMatrix())]) + return omni.usd.check_ancestral(get_prim_at_path(prim_path)) + + +def is_prim_no_delete(prim_path: str) -> bool: + """Checks whether a prim can be deleted or not from USD stage. + + .. note :: + + This function checks for the ``no_delete`` prim metadata. A prim with this + metadata set to True cannot be deleted by using the edit menu, the context menu, + or by calling the ``delete_prim`` function, for example. + + Args: + prim_path: The path to the USD prim. + + Returns: + True if prim cannot be deleted, False if it can + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # prim without the 'no_delete' metadata + >>> prims_utils.is_prim_no_delete("/World/Cube") + None + >>> # prim with the 'no_delete' metadata set to True + >>> prims_utils.is_prim_no_delete("/World/Cube") + True + """ + return get_prim_at_path(prim_path).GetMetadata("no_delete") + + +def is_prim_hidden_in_stage(prim_path: str) -> bool: + """Checks if the prim is hidden in the USd stage or not. + + .. warning :: + + This function checks for the ``hide_in_stage_window`` prim metadata. + This metadata is not related to the visibility of the prim. + + Args: + prim_path: The path to the USD prim. + + Returns: + True if prim is hidden from stage window, False if not hidden. + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # prim without the 'hide_in_stage_window' metadata + >>> prims_utils.is_prim_hidden_in_stage("/World/Cube") + None + >>> # prim with the 'hide_in_stage_window' metadata set to True + >>> prims_utils.is_prim_hidden_in_stage("/World/Cube") + True + """ + return get_prim_at_path(prim_path).GetMetadata("hide_in_stage_window") """ -USD Stage traversal. +USD Prim properties and attributes. """ -def get_first_matching_child_prim( - prim_path: str | Sdf.Path, - predicate: Callable[[Usd.Prim], bool], - stage: Usd.Stage | None = None, - traverse_instance_prims: bool = True, -) -> Usd.Prim | None: - """Recursively get the first USD Prim at the path string that passes the predicate function. +def get_prim_property(prim_path: str, property_name: str) -> Any: + """Get the attribute of the USD Prim at the given path - This function performs a depth-first traversal of the prim hierarchy starting from - :attr:`prim_path`, returning the first prim that satisfies the provided :attr:`predicate`. - It optionally supports traversal through instance prims, which are normally skipped in standard USD - traversals. + Args: + prim_path: path of the prim in the stage + property_name: name of the attribute to get - USD instance prims are lightweight copies of prototype scene structures and are not included - in default traversals unless explicitly handled. This function allows traversing into instances - when :attr:`traverse_instance_prims` is set to :attr:`True`. + Returns: + The attribute if it exists, None otherwise - .. versionchanged:: 2.3.0 + Example: - Added :attr:`traverse_instance_prims` to control whether to traverse instance prims. - By default, instance prims are now traversed. + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.get_prim_property("/World/Cube", property_name="size") + 1.0 + """ + prim = get_prim_at_path(prim_path=prim_path) + return prim.GetAttribute(property_name).Get() + + +def set_prim_property(prim_path: str, property_name: str, property_value: Any) -> None: + """Set the attribute of the USD Prim at the path Args: - prim_path: The path of the prim in the stage. - predicate: The function to test the prims against. It takes a prim as input and returns a boolean. - stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. - traverse_instance_prims: Whether to traverse instance prims. Defaults to True. + prim_path: path of the prim in the stage + property_name: name of the attribute to set + property_value: value to set the attribute to + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # given the stage: /World/Cube. Set the Cube size to 5.0 + >>> prims_utils.set_prim_property("/World/Cube", property_name="size", property_value=5.0) + """ + prim = get_prim_at_path(prim_path=prim_path) + prim.GetAttribute(property_name).Set(property_value) + + +def get_prim_attribute_names(prim_path: str, fabric: bool = False) -> list[str]: + """Get all the attribute names of a prim at the path + + Args: + prim_path: path of the prim in the stage + fabric: True for fabric stage and False for USD stage. Defaults to False. + + Raises: + Exception: If there is not a valid prim at the given path Returns: - The first prim on the path that passes the predicate. If no prim passes the predicate, it returns None. + List of the prim attribute names + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.get_prim_attribute_names("/World/Cube") + ['doubleSided', 'extent', 'orientation', 'primvars:displayColor', 'primvars:displayOpacity', + 'purpose', 'size', 'visibility', 'xformOp:orient', 'xformOp:scale', 'xformOp:translate', 'xformOpOrder'] + """ + return [attr.GetName() for attr in get_prim_at_path(prim_path=prim_path, fabric=fabric).GetAttributes()] + + +def get_prim_attribute_value(prim_path: str, attribute_name: str, fabric: bool = False) -> Any: + """Get a prim attribute value + + Args: + prim_path: path of the prim in the stage + attribute_name: name of the attribute to get + fabric: True for fabric stage and False for USD stage. Defaults to False. + + Raises: + Exception: If there is not a valid prim at the given path + + Returns: + Prim attribute value + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.get_prim_attribute_value("/World/Cube", attribute_name="size") + 1.0 + """ + attr = get_prim_at_path(prim_path=prim_path, fabric=fabric).GetAttribute(attribute_name) + if fabric: + type_name = str(attr.GetTypeName().GetAsString()) + else: + type_name = str(attr.GetTypeName()) + if type_name in SDF_type_to_Gf: + return list(attr.Get()) + else: + return attr.Get() + + +def set_prim_attribute_value(prim_path: str, attribute_name: str, value: Any, fabric: bool = False): + """Set a prim attribute value + + Args: + prim_path: path of the prim in the stage + attribute_name: name of the attribute to set + value: value to set the attribute to + fabric: True for fabric stage and False for USD stage. Defaults to False. + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # given the stage: /World/Cube. Set the Cube size to 5.0 + >>> prims_utils.set_prim_attribute_value("/World/Cube", attribute_name="size", value=5.0) + """ + attr = get_prim_at_path(prim_path=prim_path, fabric=fabric).GetAttribute(attribute_name) + if fabric: + type_name = str(attr.GetTypeName().GetAsString()) + else: + type_name = str(attr.GetTypeName()) + if isinstance(value, np.ndarray): + value = value.tolist() + if type_name in SDF_type_to_Gf: + value = np.array(value).flatten().tolist() + if fabric: + eval("attr.Set(usdrt." + SDF_type_to_Gf[type_name] + "(*value))") + else: + eval("attr.Set(" + SDF_type_to_Gf[type_name] + "(*value))") + else: + attr.Set(value) + + +def make_uninstanceable(prim_path: str | Sdf.Path, stage: Usd.Stage | None = None): + """Check if a prim and its descendants are instanced and make them uninstanceable. + + This function checks if the prim at the specified prim path and its descendants are instanced. + If so, it makes the respective prim uninstanceable by disabling instancing on the prim. + + This is useful when we want to modify the properties of a prim that is instanced. For example, if we + want to apply a different material on an instanced prim, we need to make the prim uninstanceable first. + + Args: + prim_path: The prim path to check. + stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. Raises: ValueError: If the prim path is not global (i.e: does not start with '/'). @@ -715,244 +1027,655 @@ def get_first_matching_child_prim( while len(all_prims) > 0: # get current prim child_prim = all_prims.pop(0) - # check if prim passes predicate - if predicate(child_prim): - return child_prim + # check if prim is instanced + if child_prim.IsInstance(): + # make the prim uninstanceable + child_prim.SetInstanceable(False) # add children to list - if traverse_instance_prims: - all_prims += child_prim.GetFilteredChildren(Usd.TraverseInstanceProxies()) - else: - all_prims += child_prim.GetChildren() - return None + all_prims += child_prim.GetFilteredChildren(Usd.TraverseInstanceProxies()) -def get_all_matching_child_prims( - prim_path: str | Sdf.Path, - predicate: Callable[[Usd.Prim], bool] = lambda _: True, - depth: int | None = None, - stage: Usd.Stage | None = None, - traverse_instance_prims: bool = True, -) -> list[Usd.Prim]: - """Performs a search starting from the root and returns all the prims matching the predicate. +def resolve_prim_pose( + prim: Usd.Prim, ref_prim: Usd.Prim | None = None +) -> tuple[tuple[float, float, float], tuple[float, float, float, float]]: + """Resolve the pose of a prim with respect to another prim. - This function performs a depth-first traversal of the prim hierarchy starting from - :attr:`prim_path`, returning all prims that satisfy the provided :attr:`predicate`. It optionally - supports traversal through instance prims, which are normally skipped in standard USD traversals. + Note: + This function ignores scale and skew by orthonormalizing the transformation + matrix at the final step. However, if any ancestor prim in the hierarchy + has non-uniform scale, that scale will still affect the resulting position + and orientation of the prim (because it's baked into the transform before + scale removal). - USD instance prims are lightweight copies of prototype scene structures and are not included - in default traversals unless explicitly handled. This function allows traversing into instances - when :attr:`traverse_instance_prims` is set to :attr:`True`. + In other words: scale **is not removed hierarchically**. If you need + completely scale-free poses, you must walk the transform chain and strip + scale at each level. Please open an issue if you need this functionality. - .. versionchanged:: 2.3.0 + Args: + prim: The USD prim to resolve the pose for. + ref_prim: The USD prim to compute the pose with respect to. + Defaults to None, in which case the world frame is used. - Added :attr:`traverse_instance_prims` to control whether to traverse instance prims. - By default, instance prims are now traversed. + Returns: + A tuple containing the position (as a 3D vector) and the quaternion orientation + in the (w, x, y, z) format. + + Raises: + ValueError: If the prim or ref prim is not valid. + """ + # check if prim is valid + if not prim.IsValid(): + raise ValueError(f"Prim at path '{prim.GetPath().pathString}' is not valid.") + # get prim xform + xform = UsdGeom.Xformable(prim) + prim_tf = xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + # sanitize quaternion + # this is needed, otherwise the quaternion might be non-normalized + prim_tf = prim_tf.GetOrthonormalized() + + if ref_prim is not None: + # check if ref prim is valid + if not ref_prim.IsValid(): + raise ValueError(f"Ref prim at path '{ref_prim.GetPath().pathString}' is not valid.") + # get ref prim xform + ref_xform = UsdGeom.Xformable(ref_prim) + ref_tf = ref_xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + # make sure ref tf is orthonormal + ref_tf = ref_tf.GetOrthonormalized() + # compute relative transform to get prim in ref frame + prim_tf = prim_tf * ref_tf.GetInverse() + + # extract position and orientation + prim_pos = [*prim_tf.ExtractTranslation()] + prim_quat = [prim_tf.ExtractRotationQuat().real, *prim_tf.ExtractRotationQuat().imaginary] + return tuple(prim_pos), tuple(prim_quat) + + +def resolve_prim_scale(prim: Usd.Prim) -> tuple[float, float, float]: + """Resolve the scale of a prim in the world frame. + + At an attribute level, a USD prim's scale is a scaling transformation applied to the prim with + respect to its parent prim. This function resolves the scale of the prim in the world frame, + by computing the local to world transform of the prim. This is equivalent to traversing up + the prim hierarchy and accounting for the rotations and scales of the prims. + + For instance, if a prim has a scale of (1, 2, 3) and it is a child of a prim with a scale of (4, 5, 6), + then the scale of the prim in the world frame is (4, 10, 18). Args: - prim_path: The root prim path to start the search from. - predicate: The predicate that checks if the prim matches the desired criteria. It takes a prim as input - and returns a boolean. Defaults to a function that always returns True. - depth: The maximum depth for traversal, should be bigger than zero if specified. - Defaults to None (i.e: traversal happens till the end of the tree). - stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. - traverse_instance_prims: Whether to traverse instance prims. Defaults to True. + prim: The USD prim to resolve the scale for. Returns: - A list containing all the prims matching the predicate. + The scale of the prim in the x, y, and z directions in the world frame. Raises: - ValueError: If the prim path is not global (i.e: does not start with '/'). + ValueError: If the prim is not valid. """ - # get stage handle - if stage is None: - stage = get_current_stage() - - # make paths str type if they aren't already - prim_path = str(prim_path) - # check if prim path is global - if not prim_path.startswith("/"): - raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") - # get prim - prim = stage.GetPrimAtPath(prim_path) # check if prim is valid if not prim.IsValid(): - raise ValueError(f"Prim at path '{prim_path}' is not valid.") - # check if depth is valid - if depth is not None and depth <= 0: - raise ValueError(f"Depth must be bigger than zero, got {depth}.") + raise ValueError(f"Prim at path '{prim.GetPath().pathString}' is not valid.") + # compute local to world transform + xform = UsdGeom.Xformable(prim) + world_transform = xform.ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + # extract scale + return tuple([*(v.GetLength() for v in world_transform.ExtractRotationMatrix())]) - # iterate over all prims under prim-path - # list of tuples (prim, current_depth) - all_prims_queue = [(prim, 0)] - output_prims = [] - while len(all_prims_queue) > 0: - # get current prim - child_prim, current_depth = all_prims_queue.pop(0) - # check if prim passes predicate - if predicate(child_prim): - output_prims.append(child_prim) - # add children to list - if depth is None or current_depth < depth: - # resolve prims under the current prim - if traverse_instance_prims: - children = child_prim.GetFilteredChildren(Usd.TraverseInstanceProxies()) + +def set_prim_visibility(prim: Usd.Prim, visible: bool) -> None: + """Sets the visibility of the prim in the opened stage. + + .. note:: + + The method does this through the USD API. + + Args: + prim: the USD prim + visible: flag to set the visibility of the usd prim in stage. + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> # given the stage: /World/Cube. Make the Cube not visible + >>> prim = prims_utils.get_prim_at_path("/World/Cube") + >>> prims_utils.set_prim_visibility(prim, False) + """ + imageable = UsdGeom.Imageable(prim) + if visible: + imageable.MakeVisible() + else: + imageable.MakeInvisible() + + +def get_prim_object_type(prim_path: str) -> str | None: + """Get the dynamic control object type of the USD Prim at the given path. + + If the prim at the path is of Dynamic Control type e.g.: rigid_body, joint, dof, articulation, attractor, d6joint, + then the corresponding string returned. If is an Xformable prim, then "xform" is returned. Otherwise None + is returned. + + Args: + prim_path: path of the prim in the stage + + Raises: + Exception: If the USD Prim is not a supported type. + + Returns: + String corresponding to the object type. + + Example: + + .. code-block:: python + + >>> import isaaclab.utils.prims as prims_utils + >>> + >>> prims_utils.get_prim_object_type("/World/Cube") + xform + """ + prim = get_prim_at_path(prim_path) + if prim.HasAPI(UsdPhysics.ArticulationRootAPI): + return "articulation" + elif prim.HasAPI(UsdPhysics.RigidBodyAPI): + return "rigid_body" + elif ( + prim.IsA(UsdPhysics.PrismaticJoint) or prim.IsA(UsdPhysics.RevoluteJoint) or prim.IsA(UsdPhysics.SphericalJoint) + ): + return "joint" + elif prim.IsA(UsdPhysics.Joint): + return "d6joint" + elif prim.IsA(UsdGeom.Xformable): + return "xform" + else: + return None + + +""" +Attribute - Setters. +""" + + +def safe_set_attribute_on_usd_schema(schema_api: Usd.APISchemaBase, name: str, value: Any, camel_case: bool): + """Set the value of an attribute on its USD schema if it exists. + + A USD API schema serves as an interface or API for authoring and extracting a set of attributes. + They typically derive from the :class:`pxr.Usd.SchemaBase` class. This function checks if the + attribute exists on the schema and sets the value of the attribute if it exists. + + Args: + schema_api: The USD schema to set the attribute on. + name: The name of the attribute. + value: The value to set the attribute to. + camel_case: Whether to convert the attribute name to camel case. + + Raises: + TypeError: When the input attribute name does not exist on the provided schema API. + """ + # if value is None, do nothing + if value is None: + return + # convert attribute name to camel case + if camel_case: + attr_name = to_camel_case(name, to="CC") + else: + attr_name = name + # retrieve the attribute + # reference: https://openusd.org/dev/api/_usd__page__common_idioms.html#Usd_Create_Or_Get_Property + attr = getattr(schema_api, f"Create{attr_name}Attr", None) + # check if attribute exists + if attr is not None: + attr().Set(value) + else: + # think: do we ever need to create the attribute if it doesn't exist? + # currently, we are not doing this since the schemas are already created with some defaults. + logger.error(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.") + raise TypeError(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.") + + +def safe_set_attribute_on_usd_prim(prim: Usd.Prim, attr_name: str, value: Any, camel_case: bool): + """Set the value of a attribute on its USD prim. + + The function creates a new attribute if it does not exist on the prim. This is because in some cases (such + as with shaders), their attributes are not exposed as USD prim properties that can be altered. This function + allows us to set the value of the attributes in these cases. + + Args: + prim: The USD prim to set the attribute on. + attr_name: The name of the attribute. + value: The value to set the attribute to. + camel_case: Whether to convert the attribute name to camel case. + """ + # if value is None, do nothing + if value is None: + return + # convert attribute name to camel case + if camel_case: + attr_name = to_camel_case(attr_name, to="cC") + # resolve sdf type based on value + if isinstance(value, bool): + sdf_type = Sdf.ValueTypeNames.Bool + elif isinstance(value, int): + sdf_type = Sdf.ValueTypeNames.Int + elif isinstance(value, float): + sdf_type = Sdf.ValueTypeNames.Float + elif isinstance(value, (tuple, list)) and len(value) == 3 and any(isinstance(v, float) for v in value): + sdf_type = Sdf.ValueTypeNames.Float3 + elif isinstance(value, (tuple, list)) and len(value) == 2 and any(isinstance(v, float) for v in value): + sdf_type = Sdf.ValueTypeNames.Float2 + else: + raise NotImplementedError( + f"Cannot set attribute '{attr_name}' with value '{value}'. Please modify the code to support this type." + ) + + # 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) + + # change property + omni.kit.commands.execute( + "ChangePropertyCommand", + prop_path=Sdf.Path(f"{prim.GetPath()}.{attr_name}"), + value=value, + prev=None, + type_to_create_if_not_exist=sdf_type, + usd_context_name=prim.GetStage(), + ) + + +""" +Exporting. +""" + + +def export_prim_to_file( + path: str | Sdf.Path, + source_prim_path: str | Sdf.Path, + target_prim_path: str | Sdf.Path | None = None, + stage: Usd.Stage | None = None, +): + """Exports a prim from a given stage to a USD file. + + The function creates a new layer at the provided path and copies the prim to the layer. + It sets the copied prim as the default prim in the target layer. Additionally, it updates + the stage up-axis and meters-per-unit to match the current stage. + + Args: + path: The filepath path to export the prim to. + source_prim_path: The prim path to export. + target_prim_path: The prim path to set as the default prim in the target layer. + Defaults to None, in which case the source prim path is used. + stage: The stage where the prim exists. Defaults to None, in which case the + current stage is used. + + Raises: + ValueError: If the prim paths are not global (i.e: do not start with '/'). + """ + # get stage handle + if stage is None: + stage = get_current_stage() + + # automatically casting to str in case args + # are path types + path = str(path) + source_prim_path = str(source_prim_path) + if target_prim_path is not None: + target_prim_path = str(target_prim_path) + + if not source_prim_path.startswith("/"): + raise ValueError(f"Source prim path '{source_prim_path}' is not global. It must start with '/'.") + if target_prim_path is not None and not target_prim_path.startswith("/"): + raise ValueError(f"Target prim path '{target_prim_path}' is not global. It must start with '/'.") + + # get root layer + source_layer = stage.GetRootLayer() + + # only create a new layer if it doesn't exist already + target_layer = Sdf.Find(path) + if target_layer is None: + target_layer = Sdf.Layer.CreateNew(path) + # open the target stage + target_stage = Usd.Stage.Open(target_layer) + + # update stage data + UsdGeom.SetStageUpAxis(target_stage, UsdGeom.GetStageUpAxis(stage)) + UsdGeom.SetStageMetersPerUnit(target_stage, UsdGeom.GetStageMetersPerUnit(stage)) + + # specify the prim to copy + source_prim_path = Sdf.Path(source_prim_path) + if target_prim_path is None: + target_prim_path = source_prim_path + + # copy the prim + Sdf.CreatePrimInLayer(target_layer, target_prim_path) + Sdf.CopySpec(source_layer, source_prim_path, target_layer, target_prim_path) + # set the default prim + target_layer.defaultPrim = Sdf.Path(target_prim_path).name + # resolve all paths relative to layer path + omni.usd.resolve_paths(source_layer.identifier, target_layer.identifier) + # save the stage + target_layer.Save() + + +""" +Decorators +""" + + +def apply_nested(func: Callable) -> Callable: + """Decorator to apply a function to all prims under a specified prim-path. + + The function iterates over the provided prim path and all its children to apply input function + to all prims under the specified prim path. + + If the function succeeds to apply to a prim, it will not look at the children of that prim. + This is based on the physics behavior that nested schemas are not allowed. For example, a parent prim + and its child prim cannot both have a rigid-body schema applied on them, or it is not possible to + have nested articulations. + + While traversing the prims under the specified prim path, the function will throw a warning if it + does not succeed to apply the function to any prim. This is because the user may have intended to + apply the function to a prim that does not have valid attributes, or the prim may be an instanced prim. + + Args: + func: The function to apply to all prims under a specified prim-path. The function + must take the prim-path and other arguments. It should return a boolean indicating whether + the function succeeded or not. + + Returns: + The wrapped function that applies the function to all prims under a specified prim-path. + + Raises: + ValueError: If the prim-path does not exist on the stage. + """ + + @functools.wraps(func) + def wrapper(prim_path: str | Sdf.Path, *args, **kwargs): + # map args and kwargs to function signature so we can get the stage + # note: we do this to check if stage is given in arg or kwarg + sig = inspect.signature(func) + bound_args = sig.bind(prim_path, *args, **kwargs) + # get current stage + stage = bound_args.arguments.get("stage") + if stage is None: + stage = get_current_stage() + + # get USD prim + prim: Usd.Prim = stage.GetPrimAtPath(prim_path) + # check if prim is valid + if not prim.IsValid(): + raise ValueError(f"Prim at path '{prim_path}' is not valid.") + # add iterable to check if property was applied on any of the prims + count_success = 0 + instanced_prim_paths = [] + # iterate over all prims under prim-path + all_prims = [prim] + while len(all_prims) > 0: + # get current prim + child_prim = all_prims.pop(0) + child_prim_path = child_prim.GetPath().pathString # type: ignore + # check if prim is a prototype + if child_prim.IsInstance(): + instanced_prim_paths.append(child_prim_path) + continue + # set properties + success = func(child_prim_path, *args, **kwargs) + # if successful, do not look at children + # this is based on the physics behavior that nested schemas are not allowed + if not success: + all_prims += child_prim.GetChildren() else: - children = child_prim.GetChildren() - # add children to list - all_prims_queue += [(child, current_depth + 1) for child in children] + count_success += 1 + # check if we were successful in applying the function to any prim + if count_success == 0: + logger.warning( + f"Could not perform '{func.__name__}' on any prims under: '{prim_path}'." + " This might be because of the following reasons:" + "\n\t(1) The desired attribute does not exist on any of the prims." + "\n\t(2) The desired attribute exists on an instanced prim." + f"\n\t\tDiscovered list of instanced prim paths: {instanced_prim_paths}" + ) + + return wrapper + + +def clone(func: Callable) -> Callable: + """Decorator for cloning a prim based on matching prim paths of the prim's parent. + + The decorator checks if the parent prim path matches any prim paths in the stage. If so, it clones the + spawned prim at each matching prim path. For example, if the input prim path is: ``/World/Table_[0-9]/Bottle``, + the decorator will clone the prim at each matching prim path of the parent prim: ``/World/Table_0/Bottle``, + ``/World/Table_1/Bottle``, etc. + + Note: + For matching prim paths, the decorator assumes that valid prims exist for all matching prim paths. + In case no matching prim paths are found, the decorator raises a ``RuntimeError``. + + Args: + func: The function to decorate. + + Returns: + The decorated function that spawns the prim and clones it at each matching prim path. + It returns the spawned source prim, i.e., the first prim in the list of matching prim paths. + """ + + @functools.wraps(func) + def wrapper(prim_path: str | Sdf.Path, cfg: SpawnerCfg, *args, **kwargs): + # get stage handle + stage = get_current_stage() + + # cast prim_path to str type in case its an Sdf.Path + prim_path = str(prim_path) + # check prim path is global + if not prim_path.startswith("/"): + raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") + # 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 = 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] + + # resolve prim paths for spawning and cloning + prim_paths = [f"{source_prim_path}/{asset_path}" for source_prim_path in source_prim_paths] + # spawn single instance + prim = func(prim_paths[0], cfg, *args, **kwargs) + # set the prim visibility + if hasattr(cfg, "visible"): + imageable = UsdGeom.Imageable(prim) + if cfg.visible: + imageable.MakeVisible() + else: + 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 + 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) + # 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 - return output_prims + _schemas.activate_contact_sensors(prim_paths[0]) + # clone asset using cloner API + if len(prim_paths) > 1: + cloner = lazy.isaacsim.core.cloner.Cloner(stage=stage) + # check version of Isaac Sim to determine whether clone_in_fabric is valid + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.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, + ) + # return the source prim + return prim + return wrapper -def find_first_matching_prim(prim_path_regex: str, stage: Usd.Stage | None = None) -> Usd.Prim | None: - """Find the first matching prim in the stage based on input regex expression. - Args: - prim_path_regex: The regex expression for prim path. - stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. +""" +Material bindings. +""" - Returns: - The first prim that matches input expression. If no prim matches, returns None. - Raises: - ValueError: If the prim path is not global (i.e: does not start with '/'). - """ - # get stage handle - if stage is None: - stage = get_current_stage() +@apply_nested +def bind_visual_material( + prim_path: str | Sdf.Path, + material_path: str | Sdf.Path, + stage: Usd.Stage | None = None, + stronger_than_descendants: bool = True, +): + """Bind a visual material to a prim. - # check prim path is global - if not prim_path_regex.startswith("/"): - raise ValueError(f"Prim path '{prim_path_regex}' is not global. It must start with '/'.") - # need to wrap the token patterns in '^' and '$' to prevent matching anywhere in the string - pattern = f"^{prim_path_regex}$" - compiled_pattern = re.compile(pattern) - # obtain matching prim (depth-first search) - for prim in stage.Traverse(): - # check if prim passes predicate - if compiled_pattern.match(prim.GetPath().pathString) is not None: - return prim - return None + This function is a wrapper around the USD command `BindMaterialCommand`_. + .. note:: + The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path + and all its descendants. -def find_matching_prims(prim_path_regex: str, stage: Usd.Stage | None = None) -> list[Usd.Prim]: - """Find all the matching prims in the stage based on input regex expression. + .. _BindMaterialCommand: https://docs.omniverse.nvidia.com/kit/docs/omni.usd/latest/omni.usd.commands/omni.usd.commands.BindMaterialCommand.html Args: - prim_path_regex: The regex expression for prim path. - stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. - - Returns: - A list of prims that match input expression. + prim_path: The prim path where to apply the material. + material_path: The prim path of the material to apply. + stage: The stage where the prim and material exist. + Defaults to None, in which case the current stage is used. + stronger_than_descendants: Whether the material should override the material of its descendants. + Defaults to True. Raises: - ValueError: If the prim path is not global (i.e: does not start with '/'). + ValueError: If the provided prim paths do not exist on stage. """ # get stage handle if stage is None: stage = get_current_stage() - # check prim path is global - if not prim_path_regex.startswith("/"): - raise ValueError(f"Prim path '{prim_path_regex}' is not global. It must start with '/'.") - # need to wrap the token patterns in '^' and '$' to prevent matching anywhere in the string - tokens = prim_path_regex.split("/")[1:] - tokens = [f"^{token}$" for token in tokens] - # iterate over all prims in stage (breath-first search) - all_prims = [stage.GetPseudoRoot()] - output_prims = [] - for index, token in enumerate(tokens): - token_compiled = re.compile(token) - for prim in all_prims: - for child in prim.GetAllChildren(): - if token_compiled.match(child.GetName()) is not None: - output_prims.append(child) - if index < len(tokens) - 1: - all_prims = output_prims - output_prims = [] - return output_prims - - -def find_matching_prim_paths(prim_path_regex: str, stage: Usd.Stage | None = None) -> list[str]: - """Find all the matching prim paths in the stage based on input regex expression. - - Args: - prim_path_regex: The regex expression for prim path. - stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. + # check if prim and material exists + if not stage.GetPrimAtPath(prim_path).IsValid(): + raise ValueError(f"Target prim '{material_path}' does not exist.") + if not stage.GetPrimAtPath(material_path).IsValid(): + raise ValueError(f"Visual material '{material_path}' does not exist.") - Returns: - A list of prim paths that match input expression. + # resolve token for weaker than descendants + if stronger_than_descendants: + binding_strength = "strongerThanDescendants" + else: + binding_strength = "weakerThanDescendants" + # obtain material binding API + # note: we prefer using the command here as it is more robust than the USD API + success, _ = omni.kit.commands.execute( + "BindMaterialCommand", + prim_path=prim_path, + material_path=material_path, + strength=binding_strength, + stage=stage, + ) + # return success + return success - Raises: - ValueError: If the prim path is not global (i.e: does not start with '/'). - """ - # obtain matching prims - output_prims = find_matching_prims(prim_path_regex, stage) - # convert prims to prim paths - output_prim_paths = [] - for prim in output_prims: - output_prim_paths.append(prim.GetPath().pathString) - return output_prim_paths +@apply_nested +def bind_physics_material( + prim_path: str | Sdf.Path, + material_path: str | Sdf.Path, + stage: Usd.Stage | None = None, + stronger_than_descendants: bool = True, +): + """Bind a physics material to a prim. -def find_global_fixed_joint_prim( - prim_path: str | Sdf.Path, check_enabled_only: bool = False, stage: Usd.Stage | None = None -) -> UsdPhysics.Joint | None: - """Find the fixed joint prim under the specified prim path that connects the target to the simulation world. + `Physics material`_ can be applied only to a prim with physics-enabled on them. This includes having + collision APIs, or deformable body APIs, or being a particle system. In case the prim does not have + any of these APIs, the function will not apply the material and return False. - A joint is a connection between two bodies. A fixed joint is a joint that does not allow relative motion - between the two bodies. When a fixed joint has only one target body, it is considered to attach the body - to the simulation world. + .. note:: + The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path + and all its descendants. - This function finds the fixed joint prim that has only one target under the specified prim path. If no such - fixed joint prim exists, it returns None. + .. _Physics material: https://isaac-sim.github.io/IsaacLab/main/source/api/lab/isaaclab.sim.html#isaaclab.sim.SimulationCfg.physics_material Args: - prim_path: The prim path to search for the fixed joint prim. - check_enabled_only: Whether to consider only enabled fixed joints. Defaults to False. - If False, then all joints (enabled or disabled) are considered. - stage: The stage where the prim exists. Defaults to None, in which case the current stage is used. - - Returns: - The fixed joint prim that has only one target. If no such fixed joint prim exists, it returns None. + prim_path: The prim path where to apply the material. + material_path: The prim path of the material to apply. + stage: The stage where the prim and material exist. + Defaults to None, in which case the current stage is used. + stronger_than_descendants: Whether the material should override the material of its descendants. + Defaults to True. Raises: - ValueError: If the prim path is not global (i.e: does not start with '/'). - ValueError: If the prim path does not exist on the stage. + ValueError: If the provided prim paths do not exist on stage. """ # get stage handle if stage is None: stage = get_current_stage() - # check prim path is global - if not prim_path.startswith("/"): - raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.") - - # check if prim exists + # check if prim and material exists + if not stage.GetPrimAtPath(prim_path).IsValid(): + raise ValueError(f"Target prim '{material_path}' does not exist.") + if not stage.GetPrimAtPath(material_path).IsValid(): + raise ValueError(f"Physics material '{material_path}' does not exist.") + # get USD prim prim = stage.GetPrimAtPath(prim_path) - if not prim.IsValid(): - raise ValueError(f"Prim at path '{prim_path}' is not valid.") + # check if prim has collision applied on it + has_physics_scene_api = prim.HasAPI(PhysxSchema.PhysxSceneAPI) + has_collider = prim.HasAPI(UsdPhysics.CollisionAPI) + has_deformable_body = prim.HasAPI(PhysxSchema.PhysxDeformableBodyAPI) + has_particle_system = prim.IsA(PhysxSchema.PhysxParticleSystem) + if not (has_physics_scene_api or has_collider or has_deformable_body or has_particle_system): + logger.debug( + f"Cannot apply physics material '{material_path}' on prim '{prim_path}'. It is neither a" + " PhysX scene, collider, a deformable body, nor a particle system." + ) + return False - fixed_joint_prim = None - # we check all joints under the root prim and classify the asset as fixed base if there exists - # a fixed joint that has only one target (i.e. the root link). - for prim in Usd.PrimRange(prim): - # note: ideally checking if it is FixedJoint would have been enough, but some assets use "Joint" as the - # schema name which makes it difficult to distinguish between the two. - joint_prim = UsdPhysics.Joint(prim) - if joint_prim: - # if check_enabled_only is True, we only consider enabled joints - if check_enabled_only and not joint_prim.GetJointEnabledAttr().Get(): - continue - # check body 0 and body 1 exist - body_0_exist = joint_prim.GetBody0Rel().GetTargets() != [] - body_1_exist = joint_prim.GetBody1Rel().GetTargets() != [] - # if either body 0 or body 1 does not exist, we have a fixed joint that connects to the world - if not (body_0_exist and body_1_exist): - fixed_joint_prim = joint_prim - break + # obtain material binding API + if prim.HasAPI(UsdShade.MaterialBindingAPI): + material_binding_api = UsdShade.MaterialBindingAPI(prim) + else: + material_binding_api = UsdShade.MaterialBindingAPI.Apply(prim) + # obtain the material prim - return fixed_joint_prim + material = UsdShade.Material(stage.GetPrimAtPath(material_path)) + # resolve token for weaker than descendants + if stronger_than_descendants: + binding_strength = UsdShade.Tokens.strongerThanDescendants + else: + binding_strength = UsdShade.Tokens.weakerThanDescendants + # apply the material + material_binding_api.Bind(material, bindingStrength=binding_strength, materialPurpose="physics") # type: ignore + # return success + return True """ @@ -1033,39 +1756,3 @@ class TableVariants: f"Setting variant selection '{variant_selection}' for variant set '{variant_set_name}' on" f" prim '{prim_path}'." ) - - -# --- Colored formatter --- -class ColoredFormatter(logging.Formatter): - COLORS = { - "WARNING": "\033[33m", # orange/yellow - "ERROR": "\033[31m", # red - "CRITICAL": "\033[31m", # red - "INFO": "\033[0m", # reset - "DEBUG": "\033[0m", - } - RESET = "\033[0m" - - def format(self, record): - color = self.COLORS.get(record.levelname, self.RESET) - message = super().format(record) - return f"{color}{message}{self.RESET}" - - -# --- Custom rate-limited warning filter --- -class RateLimitFilter(logging.Filter): - def __init__(self, interval_seconds=5): - super().__init__() - self.interval = interval_seconds - self.last_emitted = {} - - def filter(self, record): - """Allow WARNINGs only once every few seconds per message.""" - if record.levelno != logging.WARNING: - return True - now = time.time() - msg_key = record.getMessage() - if msg_key not in self.last_emitted or (now - self.last_emitted[msg_key]) > self.interval: - self.last_emitted[msg_key] = now - return True - return False diff --git a/source/isaaclab/isaaclab/sim/utils/semantics.py b/source/isaaclab/isaaclab/sim/utils/semantics.py new file mode 100644 index 00000000000..4ee181b1a18 --- /dev/null +++ b/source/isaaclab/isaaclab/sim/utils/semantics.py @@ -0,0 +1,276 @@ +# 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 carb +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 + + +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: + carb.log_warn("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: + carb.log_warn(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: + carb.log_warn("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: + carb.log_warn(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: + carb.log_warn("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: + carb.log_warn(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: + carb.log_warn( + 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: + carb.log_warn(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 171926ab8bf..c5209465da3 100644 --- a/source/isaaclab/isaaclab/sim/utils/stage.py +++ b/source/isaaclab/isaaclab/sim/utils/stage.py @@ -13,21 +13,18 @@ import carb import omni import omni.kit.app -from isaacsim.core.utils import stage as sim_stage -from isaacsim.core.utils.carb import get_carb_setting -from isaacsim.core.version import get_version -from omni.metrics.assembler.core import get_metrics_assembler_interface -from omni.usd.commands import DeletePrimsCommand from pxr import Sdf, Usd, UsdGeom, UsdUtils +from isaaclab import lazy + # 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 +# _context is a singleton design in Isaac Sim and for that reason +# until we fully replace all modules that reference the singleton (such as XformPrim, Prim ...), +# we have to point that singleton to this _context. +lazy.isaacsim.core.utils.stage._context = _context AXES_TOKEN = { "X": UsdGeom.Tokens.x, @@ -60,13 +57,10 @@ def attach_stage_to_usd_context(attaching_early: bool = False): Args: attaching_early: Whether to attach the stage to the usd context before stage is created. Defaults to False. """ - - from isaacsim.core.simulation_manager import SimulationManager - from isaaclab.sim.simulation_context import SimulationContext # if Isaac Sim version is less than 5.0, stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: return @@ -81,7 +75,7 @@ def attach_stage_to_usd_context(attaching_early: bool = False): # this carb flag is equivalent to if rendering is enabled carb_setting = carb.settings.get_settings() - is_rendering_enabled = get_carb_setting(carb_setting, "/physics/fabricUpdateTransformations") + is_rendering_enabled = carb_setting.get("/physics/fabricUpdateTransformations") # if rendering is not enabled, we don't need to attach it if not is_rendering_enabled: @@ -98,7 +92,7 @@ def attach_stage_to_usd_context(attaching_early: bool = False): SimulationContext.instance().skip_next_stage_open_callback() # disable stage open callback to avoid clearing callbacks - SimulationManager.enable_stage_open_callback(False) + lazy.isaacsim.core.simulation_manager.SimulationManager.enable_stage_open_callback(False) # enable physics fabric SimulationContext.instance()._physics_context.enable_fabric(True) @@ -111,7 +105,7 @@ def attach_stage_to_usd_context(attaching_early: bool = False): physx_sim_interface.attach_stage(stage_id) # re-enable stage open callback - SimulationManager.enable_stage_open_callback(True) + lazy.isaacsim.core.simulation_manager.SimulationManager.enable_stage_open_callback(True) def is_current_stage_in_memory() -> bool: @@ -152,7 +146,7 @@ def use_stage(stage: Usd.Stage) -> Generator[None, None, None]: .. code-block:: python >>> from pxr import Usd - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_in_memory = Usd.Stage.CreateInMemory() >>> with stage_utils.use_stage(stage_in_memory): @@ -160,7 +154,7 @@ 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])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.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 @@ -194,7 +188,7 @@ def get_current_stage(fabric: bool = False) -> Usd.Stage: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.get_current_stage() Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x7fba6c04f840:World7.usd'), @@ -215,7 +209,7 @@ def get_current_stage_id() -> int: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.get_current_stage_id() 1234567890 @@ -235,7 +229,7 @@ def update_stage() -> None: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.update_stage() """ @@ -253,7 +247,7 @@ def set_stage_up_axis(axis: str = "z") -> None: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> # set stage up axis to Y-up >>> stage_utils.set_stage_up_axis("y") @@ -277,7 +271,7 @@ def get_stage_up_axis() -> str: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.get_stage_up_axis() Z @@ -297,49 +291,44 @@ def clear_stage(predicate: typing.Callable[[str], bool] | None = None) -> None: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> # clear the whole stage >>> stage_utils.clear_stage() >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Delete only the prims of type Cube - >>> predicate = lambda path: prims_utils.get_prim_type_name(path) == "Cube" + >>> predicate = lambda path: prims_utils.from_prim_path_get_type_name(path) == "Cube" >>> stage_utils.clear_stage(predicate) # after the execution the stage will be /World """ # Note: Need to import this here to prevent circular dependencies. - # TODO(Octi): uncomment and remove sim import below after prim_utils replacement merged - from isaacsim.core.utils.prims import ( # isaaclab.utils.prims import ( - get_all_matching_child_prims, - get_prim_path, - is_prim_ancestral, - is_prim_hidden_in_stage, - is_prim_no_delete, - ) - - def default_predicate(prim_path: str): - # prim = get_prim_at_path(prim_path) - # skip prims that we cannot delete - if is_prim_no_delete(prim_path): + from .prims import get_all_matching_child_prims + + def default_predicate(prim: Usd.Prim) -> bool: + prim_path = prim.GetPath().pathString + if prim_path == "/": return False - if is_prim_hidden_in_stage(prim_path): + if prim_path.startswith("/Render"): return False - if is_prim_ancestral(prim_path): + if prim.GetMetadata("no_delete"): return False - if prim_path == "/": + if prim.GetMetadata("hide_in_stage_window"): return False - if prim_path.startswith("/Render"): + if omni.usd.check_ancestral(prim): return False return True + def predicate_from_path(prim: Usd.Prim) -> bool: + if predicate is None: + return default_predicate(prim) + return predicate(prim.GetPath().pathString) + if predicate is None: prims = get_all_matching_child_prims("/", default_predicate) - prim_paths_to_delete = [get_prim_path(prim) for prim in prims] - DeletePrimsCommand(prim_paths_to_delete).do() else: - prims = get_all_matching_child_prims("/", predicate) - prim_paths_to_delete = [get_prim_path(prim) for prim in prims] - DeletePrimsCommand(prim_paths_to_delete).do() + prims = get_all_matching_child_prims("/", predicate_from_path) + prim_paths_to_delete = [prim.GetPath().pathString for prim in prims] + omni.usd.commands.DeletePrimsCommand(prim_paths_to_delete).do() if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False: omni.kit.app.get_app_interface().update() @@ -352,7 +341,7 @@ def print_stage_prim_paths(fabric: bool = False) -> None: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> stage_utils.print_stage_prim_paths() @@ -367,9 +356,7 @@ def print_stage_prim_paths(fabric: bool = False) -> None: /OmniverseKit_Right """ # Note: Need to import this here to prevent circular dependencies. - # TODO(Octi): uncomment and remove sim import below after prim_utils replacement merged - # from isaaclab.utils.prims import get_prim_path - from isaacsim.core.utils.prims import get_prim_path + from .prims import get_prim_path for prim in traverse_stage(fabric=fabric): prim_path = get_prim_path(prim) @@ -398,7 +385,7 @@ def add_reference_to_stage(usd_path: str, prim_path: str, prim_type: str = "Xfor .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> # load an USD file (franka.usd) to the stage under the path /World/panda >>> prim = stage_utils.add_reference_to_stage( @@ -420,7 +407,7 @@ def add_reference_to_stage(usd_path: str, prim_path: str, prim_type: str = "Xfor # logger.info(f"Could not get Sdf layer for {usd_path}") else: stage_id = UsdUtils.StageCache.Get().GetId(stage).ToLongInt() - ret_val = get_metrics_assembler_interface().check_layers( + ret_val = lazy.omni_metrics_assembler_core.get_metrics_assembler_interface().check_layers( stage.GetRootLayer().identifier, sdf_layer.identifier, stage_id ) if ret_val["ret_val"]: @@ -451,7 +438,7 @@ def create_new_stage() -> Usd.Stage: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.create_new_stage() Usd.Stage.Open(rootLayer=Sdf.Find('anon:0x7fba6c04f840:World7.usd'), @@ -471,14 +458,14 @@ def create_new_stage_in_memory() -> Usd.Stage: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.create_new_stage_in_memory() Usd.Stage.Open(rootLayer=Sdf.Find('anon:0xf7b00e0:tmp.usda'), sessionLayer=Sdf.Find('anon:0xf7cd2e0:tmp-session.usda'), pathResolverContext=) """ - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.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" @@ -505,7 +492,7 @@ def open_stage(usd_path: str) -> bool: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.open_stage("/home//Documents/Assets/Robots/FrankaRobotics/FrankaPanda/franka.usd") True @@ -536,7 +523,7 @@ def save_stage(usd_path: str, save_and_reload_in_place=True) -> bool: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.save_stage("/home//Documents/Save/stage.usd") True @@ -572,14 +559,14 @@ def close_stage(callback_fn: typing.Callable | None = None) -> bool: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.close_stage() True .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> def callback(*args, **kwargs): ... print("callback:", args, kwargs) @@ -607,7 +594,7 @@ def traverse_stage(fabric=False) -> typing.Iterable: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01, /World/Cube_02. >>> # Traverse through prims in the stage @@ -636,7 +623,7 @@ def is_stage_loading() -> bool: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.is_stage_loading() False @@ -675,7 +662,7 @@ def set_stage_units(stage_units_in_meters: float) -> None: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.set_stage_units(1.0) """ @@ -711,7 +698,7 @@ def get_stage_units() -> float: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> stage_utils.get_stage_units() 1.0 @@ -733,7 +720,7 @@ def get_next_free_path(path: str, parent: str = None) -> str: .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> >>> # given the stage: /World/Cube, /World/Cube_01. >>> # Get the next available path for /World/Cube @@ -761,7 +748,7 @@ def remove_deleted_references(): .. code-block:: python - >>> from isaaclab.sim.utils import stage as stage_utils + >>> import isaaclab.sim.utils.stage as stage_utils >>> stage_utils.remove_deleted_references() Removed 2 deleted payload items from Removed 1 deleted reference items from diff --git a/source/isaaclab/isaaclab/terrains/utils.py b/source/isaaclab/isaaclab/terrains/utils.py index 1c55a9325b2..92aa96975b9 100644 --- a/source/isaaclab/isaaclab/terrains/utils.py +++ b/source/isaaclab/isaaclab/terrains/utils.py @@ -80,10 +80,10 @@ def create_prim_from_mesh(prim_path: str, mesh: trimesh.Trimesh, **kwargs): physics_material: The physics material to apply. Defaults to None. """ # need to import these here to prevent isaacsim launching when importing this module - import isaacsim.core.utils.prims as prim_utils from pxr import UsdGeom import isaaclab.sim as sim_utils + import isaaclab.sim.utils.prims as prim_utils # create parent prim prim_utils.create_prim(prim_path, "Xform") diff --git a/source/isaaclab/isaaclab/ui/widgets/image_plot.py b/source/isaaclab/isaaclab/ui/widgets/image_plot.py index 08497ba7002..7e02bcd0189 100644 --- a/source/isaaclab/isaaclab/ui/widgets/image_plot.py +++ b/source/isaaclab/isaaclab/ui/widgets/image_plot.py @@ -5,21 +5,17 @@ import logging import numpy as np -from contextlib import suppress from matplotlib import cm from typing import TYPE_CHECKING, Optional import carb import omni -with suppress(ImportError): - # isaacsim.gui is not available when running in headless mode. - import isaacsim.gui.components.ui_utils +from isaaclab import lazy from .ui_widget_wrapper import UIWidgetWrapper if TYPE_CHECKING: - import isaacsim.gui.components import omni.ui # import logger @@ -164,7 +160,7 @@ def _build_widget(self): # Write the leftmost label for what this plot is omni.ui.Label( self._label, - width=isaacsim.gui.components.ui_utils.LABEL_WIDTH, + width=lazy.isaacsim.gui.components.ui_utils.LABEL_WIDTH, alignment=omni.ui.Alignment.LEFT_TOP, ) with omni.ui.Frame(width=self._aspect_ratio * self._widget_height, height=self._widget_height): @@ -202,7 +198,7 @@ def _build_mode_frame(self): def _change_mode(value): self._curr_mode = value - isaacsim.gui.components.ui_utils.dropdown_builder( + lazy.isaacsim.gui.components.ui_utils.dropdown_builder( label="Mode", type="dropdown", items=["Original", "Normalization", "Colorization"], diff --git a/source/isaaclab/isaaclab/ui/widgets/line_plot.py b/source/isaaclab/isaaclab/ui/widgets/line_plot.py index e31410e6b6b..3fd27dce006 100644 --- a/source/isaaclab/isaaclab/ui/widgets/line_plot.py +++ b/source/isaaclab/isaaclab/ui/widgets/line_plot.py @@ -7,20 +7,17 @@ import colorsys import numpy as np -from contextlib import suppress from typing import TYPE_CHECKING import omni -from isaacsim.core.api.simulation_context import SimulationContext -with suppress(ImportError): - # isaacsim.gui is not available when running in headless mode. - import isaacsim.gui.components.ui_utils +from isaaclab import lazy +from isaaclab.sim import SimulationContext from .ui_widget_wrapper import UIWidgetWrapper if TYPE_CHECKING: - import isaacsim.gui.components + import isaacsim.gui.components # noqa: F401 import omni.ui @@ -402,7 +399,7 @@ def _build_legends_frame(self): max_legend = max([len(legend) for legend in self._legends]) CHAR_WIDTH = 8 with omni.ui.VGrid( - row_height=isaacsim.gui.components.ui_utils.LABEL_HEIGHT, + row_height=lazy.isaacsim.gui.components.ui_utils.LABEL_HEIGHT, column_width=max_legend * CHAR_WIDTH + 6, ): for idx in range(len(self._y_data)): @@ -447,7 +444,7 @@ def _build_limits_frame(self): with omni.ui.HStack(): omni.ui.Label( "Limits", - width=isaacsim.gui.components.ui_utils.LABEL_WIDTH, + width=lazy.isaacsim.gui.components.ui_utils.LABEL_WIDTH, alignment=omni.ui.Alignment.LEFT_CENTER, ) @@ -465,10 +462,10 @@ def _build_limits_frame(self): omni.ui.Button( "Re-Scale", - width=isaacsim.gui.components.ui_utils.BUTTON_WIDTH, + width=lazy.isaacsim.gui.components.ui_utils.BUTTON_WIDTH, clicked_fn=self._rescale_btn_pressed, alignment=omni.ui.Alignment.LEFT_CENTER, - style=isaacsim.gui.components.ui_utils.get_style(), + style=lazy.isaacsim.gui.components.ui_utils.get_style(), ) omni.ui.CheckBox(model=self._autoscale_model, tooltip="", width=4) @@ -503,7 +500,7 @@ def _filter_changed(value): self.clear() self._filter_mode = value - isaacsim.gui.components.ui_utils.dropdown_builder( + lazy.isaacsim.gui.components.ui_utils.dropdown_builder( label="Filter", type="dropdown", items=["None", "Lowpass", "Integrate", "Derivative"], @@ -517,10 +514,10 @@ def _toggle_paused(): # Button omni.ui.Button( "Play/Pause", - width=isaacsim.gui.components.ui_utils.BUTTON_WIDTH, + width=lazy.isaacsim.gui.components.ui_utils.BUTTON_WIDTH, clicked_fn=_toggle_paused, alignment=omni.ui.Alignment.LEFT_CENTER, - style=isaacsim.gui.components.ui_utils.get_style(), + style=lazy.isaacsim.gui.components.ui_utils.get_style(), ) def _create_ui_widget(self): diff --git a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py index bf4d43a4d2e..6d0fecee724 100644 --- a/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py +++ b/source/isaaclab/isaaclab/ui/widgets/manager_live_visualizer.py @@ -12,9 +12,9 @@ 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 import SimulationContext from isaaclab.utils import configclass from .image_plot import ImagePlot diff --git a/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py b/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py index ec084098dcb..37dd7b9df7f 100644 --- a/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py +++ b/source/isaaclab/isaaclab/ui/xr_widgets/instruction_widget.py @@ -9,12 +9,12 @@ from typing import Any, TypeAlias import omni.kit.commands +import omni.kit.xr import omni.ui as ui -from isaacsim.core.utils.prims import delete_prim, get_prim_at_path -from omni.kit.xr.scene_view.utils import UiContainer, WidgetComponent -from omni.kit.xr.scene_view.utils.spatial_source import SpatialSource from pxr import Gf +from isaaclab.sim.utils.prims import delete_prim, get_prim_at_path + Vec3Type: TypeAlias = Gf.Vec3f | Gf.Vec3d camera_facing_widget_container = {} @@ -128,7 +128,7 @@ def show_instruction( font_size: float = 0.1, text_color: int = 0xFFFFFFFF, target_prim_path: str = "/newPrim", -) -> UiContainer | None: +) -> omni.kit.xr.scene_view.utils.UiContainer | None: """Create and display an instruction widget with the given text. The widget size is computed from the text and font size, wrapping content @@ -148,7 +148,7 @@ def show_instruction( target_prim_path (str): Prim path where the widget prim will be created/copied. Returns: - UiContainer | None: The container that owns the instruction widget, or ``None`` if creation failed. + omni.kit.xr.scene_view.utils.UiContainer | None: The container that owns the instruction widget, or ``None`` if creation failed. """ global camera_facing_widget_container, camera_facing_widget_timers @@ -173,7 +173,7 @@ def show_instruction( width, height, wrapped_text = compute_widget_dimensions(text, font_size, max_width, min_width) # Create the widget component. - widget_component = WidgetComponent( + widget_component = omni.kit.xr.scene_view.utils.WidgetComponent( SimpleTextWidget, width=width, height=height, @@ -191,15 +191,17 @@ def show_instruction( space_stack = [] if copied_prim is not None: - space_stack.append(SpatialSource.new_prim_path_source(target_prim_path)) + space_stack.append( + omni.kit.xr.scene_view.utils.spatial_source.SpatialSource.new_prim_path_source(target_prim_path) + ) space_stack.extend([ - SpatialSource.new_translation_source(translation), - SpatialSource.new_look_at_camera_source(), + omni.kit.xr.scene_view.utils.spatial_source.SpatialSource.new_translation_source(translation), + omni.kit.xr.scene_view.utils.spatial_source.SpatialSource.new_look_at_camera_source(), ]) # Create the UI container with the widget. - container = UiContainer( + container = omni.kit.xr.scene_view.utils.UiContainer( widget_component, space_stack=space_stack, ) diff --git a/source/isaaclab/isaaclab/utils/lazy_importer.py b/source/isaaclab/isaaclab/utils/lazy_importer.py new file mode 100644 index 00000000000..7cf98d42215 --- /dev/null +++ b/source/isaaclab/isaaclab/utils/lazy_importer.py @@ -0,0 +1,39 @@ +# 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 importlib +from typing import Any + + +class LazyImporter: + """Lightweight proxy that imports a module on first use. + + This is intended for heavy, optional dependencies (for example ``isaacsim``) + so importing :mod:`isaaclab` does not eagerly import them. + + Example + ------- + .. code-block:: python + + isaacsim = LazyImporter("isaacsim") + app = isaacsim.SimulationApp(...) + """ + + def __init__(self, module_name: str, module: Any | None = None): + # ``module`` is accepted for backwards compatibility with the old API + # but ignored by the new implementation. + self._module_name = module_name + self._module: Any | None = None + + def _load(self): + if self._module is None: + self._module = importlib.import_module(self._module_name) + return self._module + + def __getattr__(self, item: str) -> Any: # pragma: no cover - thin wrapper + return getattr(self._load(), item) + + def __repr__(self) -> str: + return f"" diff --git a/source/isaaclab/isaaclab/utils/string.py b/source/isaaclab/isaaclab/utils/string.py index 43a2fa0b310..22e7f0e66be 100644 --- a/source/isaaclab/isaaclab/utils/string.py +++ b/source/isaaclab/isaaclab/utils/string.py @@ -370,3 +370,46 @@ def resolve_matching_names_values( ) # return return index_list, names_list, values_list + + +def find_unique_string_name(initial_name: str, is_unique_fn: Callable[[str], bool]) -> str: + """Find a unique string name based on the predicate function provided. + The string is appended with "_N", where N is a natural number till the resultant string + is unique. + Args: + initial_name (str): The initial string name. + is_unique_fn (Callable[[str], bool]): The predicate function to validate against. + Returns: + str: A unique string based on input function. + """ + if is_unique_fn(initial_name): + return initial_name + iterator = 1 + result = initial_name + "_" + str(iterator) + while not is_unique_fn(result): + result = initial_name + "_" + str(iterator) + iterator += 1 + return result + + +def find_root_prim_path_from_regex(prim_path_regex: str) -> tuple[str, int]: + """Find the first prim above the regex pattern prim and its position. + Args: + prim_path_regex (str): full prim path including the regex pattern prim. + Returns: + Tuple[str, int]: First position is the prim path to the parent of the regex prim. + Second position represents the level of the regex prim in the USD stage tree representation. + """ + prim_paths_list = str(prim_path_regex).split("/") + root_idx = None + for prim_path_idx in range(len(prim_paths_list)): + chars = set("[]*|^") + if any((c in chars) for c in prim_paths_list[prim_path_idx]): + root_idx = prim_path_idx + break + root_prim_path = None + tree_level = None + if root_idx is not None: + root_prim_path = "/".join(prim_paths_list[:root_idx]) + tree_level = root_idx + return root_prim_path, tree_level diff --git a/source/isaaclab/test/assets/check_fixed_base_assets.py b/source/isaaclab/test/assets/check_fixed_base_assets.py index 8a07be1c413..cafb4a561f6 100644 --- a/source/isaaclab/test/assets/check_fixed_base_assets.py +++ b/source/isaaclab/test/assets/check_fixed_base_assets.py @@ -35,9 +35,8 @@ import numpy as np import torch -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation ## diff --git a/source/isaaclab/test/assets/test_articulation.py b/source/isaaclab/test/assets/test_articulation.py index 3dda2c89396..abc8765fbdc 100644 --- a/source/isaaclab/test/assets/test_articulation.py +++ b/source/isaaclab/test/assets/test_articulation.py @@ -8,10 +8,9 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher -HEADLESS = True - # launch omniverse app simulation_app = AppLauncher(headless=True).app @@ -20,11 +19,10 @@ import ctypes import torch -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.version import get_version import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.utils.math as math_utils import isaaclab.utils.string as string_utils from isaaclab.actuators import ActuatorBase, IdealPDActuatorCfg, ImplicitActuatorCfg @@ -1957,7 +1955,7 @@ def test_spatial_tendons(sim, num_articulations, device): device: The device to run the simulation on """ # skip test if Isaac Sim version is less than 5.0 - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: pytest.skip("Spatial tendons are not supported in Isaac Sim < 5.0. Please update to Isaac Sim 5.0 or later.") return articulation_cfg = generate_articulation_cfg(articulation_type="spatial_tendon_test_asset") @@ -2023,7 +2021,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # The static friction must be set first to be sure the dynamic friction is not greater than static # when both are set. articulation.write_joint_friction_coefficient_to_sim(friction) - if int(get_version()[2]) >= 5: + if int(lazy.isaacsim.core.version.get_version()[2]) >= 5: articulation.write_joint_dynamic_friction_coefficient_to_sim(dynamic_friction) articulation.write_joint_viscous_friction_coefficient_to_sim(viscous_friction) articulation.write_data_to_sim() @@ -2034,7 +2032,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # update buffers articulation.update(sim.cfg.dt) - if int(get_version()[2]) >= 5: + if int(lazy.isaacsim.core.version.get_version()[2]) >= 5: friction_props_from_sim = articulation.root_physx_view.get_dof_friction_properties() joint_friction_coeff_sim = friction_props_from_sim[:, :, 0] joint_dynamic_friction_coeff_sim = friction_props_from_sim[:, :, 1] @@ -2048,7 +2046,7 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground # For Isaac Sim >= 5.0: also test the combined API that can set dynamic and viscous via # write_joint_friction_coefficient_to_sim; reset the sim to isolate this path. - if int(get_version()[2]) >= 5: + if int(lazy.isaacsim.core.version.get_version()[2]) >= 5: # Reset simulator to ensure a clean state for the alternative API path sim.reset() diff --git a/source/isaaclab/test/assets/test_deformable_object.py b/source/isaaclab/test/assets/test_deformable_object.py index 2d589573e69..3044d973420 100644 --- a/source/isaaclab/test/assets/test_deformable_object.py +++ b/source/isaaclab/test/assets/test_deformable_object.py @@ -20,11 +20,11 @@ import torch import carb -import isaacsim.core.utils.prims as prim_utils import pytest from flaky import flaky import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.utils.math as math_utils from isaaclab.assets import DeformableObject, DeformableObjectCfg from isaaclab.sim import build_simulation_context diff --git a/source/isaaclab/test/assets/test_rigid_object.py b/source/isaaclab/test/assets/test_rigid_object.py index 6a0dc77b861..e2eaef091d5 100644 --- a/source/isaaclab/test/assets/test_rigid_object.py +++ b/source/isaaclab/test/assets/test_rigid_object.py @@ -20,11 +20,11 @@ import torch from typing import Literal -import isaacsim.core.utils.prims as prim_utils import pytest from flaky import flaky import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import RigidObject, RigidObjectCfg from isaaclab.sim import build_simulation_context from isaaclab.sim.spawners import materials diff --git a/source/isaaclab/test/assets/test_rigid_object_collection.py b/source/isaaclab/test/assets/test_rigid_object_collection.py index 876a2904bf1..b11d046ad81 100644 --- a/source/isaaclab/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab/test/assets/test_rigid_object_collection.py @@ -19,10 +19,10 @@ import ctypes import torch -import isaacsim.core.utils.prims as prim_utils import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import RigidObjectCfg, RigidObjectCollection, RigidObjectCollectionCfg from isaaclab.sim import build_simulation_context from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/source/isaaclab/test/assets/test_surface_gripper.py b/source/isaaclab/test/assets/test_surface_gripper.py index c2f81143f59..1e0334e8ba6 100644 --- a/source/isaaclab/test/assets/test_surface_gripper.py +++ b/source/isaaclab/test/assets/test_surface_gripper.py @@ -9,6 +9,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -18,11 +19,10 @@ import torch -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.version import get_version import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ( Articulation, @@ -173,7 +173,7 @@ def test_initialization(sim, num_articulations, device, add_ground_plane) -> Non device: The device to run the test on. add_ground_plane: Whether to add a ground plane to the simulation. """ - isaac_sim_version = get_version() + isaac_sim_version = lazy.isaacsim.core.version.get_version() if int(isaac_sim_version[2]) < 5: return surface_gripper_cfg, articulation_cfg = generate_surface_gripper_cfgs(kinematic_enabled=False) @@ -208,7 +208,7 @@ def test_initialization(sim, num_articulations, device, add_ground_plane) -> Non @pytest.mark.isaacsim_ci def test_raise_error_if_not_cpu(sim, device, add_ground_plane) -> None: """Test that the SurfaceGripper raises an error if the device is not CPU.""" - isaac_sim_version = get_version() + isaac_sim_version = lazy.isaacsim.core.version.get_version() if int(isaac_sim_version[2]) < 5: return num_articulations = 1 diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index e454171e9b1..f1e02f684ea 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -14,14 +15,13 @@ import torch -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.assets import Articulation from isaaclab.controllers import DifferentialIKController, DifferentialIKControllerCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.math import ( # isort:skip compute_pose_error, @@ -55,7 +55,7 @@ def sim(): cfg.func("/World/GroundPlane", cfg) # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") env_prim_paths = cloner.generate_paths("/World/envs/env", num_envs) # create source prim diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index d1cf73706ee..af60c04a508 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -14,17 +15,16 @@ import torch -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.assets import Articulation from isaaclab.controllers import OperationalSpaceController, OperationalSpaceControllerCfg from isaaclab.markers import VisualizationMarkers from isaaclab.markers.config import FRAME_MARKER_CFG from isaaclab.sensors import ContactSensor, ContactSensorCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.math import ( apply_delta_pose, combine_frame_transforms, @@ -72,7 +72,7 @@ def sim(): ) # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") env_prim_paths = cloner.generate_paths("/World/envs/env", num_envs) # create source prim diff --git a/source/isaaclab/test/deps/isaacsim/check_camera.py b/source/isaaclab/test/deps/isaacsim/check_camera.py index 15bc66e3746..74dab033db6 100644 --- a/source/isaaclab/test/deps/isaacsim/check_camera.py +++ b/source/isaaclab/test/deps/isaacsim/check_camera.py @@ -21,6 +21,8 @@ import argparse +from isaaclab import lazy + # isaaclab from isaaclab.app import AppLauncher @@ -45,15 +47,12 @@ import os import random -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep -from isaacsim.core.api.world import World -from isaacsim.core.prims import Articulation, RigidPrim, SingleGeometryPrim, SingleRigidPrim -from isaacsim.core.utils.viewports import set_camera_view from PIL import Image, ImageChops from pxr import Gf, UsdGeom import isaaclab.sim.utils.nucleus as nucleus_utils +import isaaclab.sim.utils.prims as prim_utils # check nucleus connection if nucleus_utils.get_assets_root_path() is None: @@ -71,9 +70,9 @@ def main(): """Runs a camera sensor from isaaclab.""" # Load kit helper - world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu") + world = lazy.isaacsim.core.api.world.World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu") # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) + lazy.isaacsim.core.utils.viewports.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Enable flatcache which avoids passing data over to USD structure # this speeds up the read-write operation of GPU buffers @@ -108,8 +107,8 @@ def main(): semantic_label=prim_type, ) # add rigid properties - SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) - rigid_obj = SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) + lazy.isaacsim.core.prims.SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) + rigid_obj = lazy.isaacsim.core.prims.SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) # cast to geom prim geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim) # set random color @@ -153,9 +152,9 @@ def main(): # Create a view of the stuff we want to see if args_cli.scenario == "cube": - view: RigidPrim = world.scene.add(RigidPrim("/World/Objects/.*", name="my_object")) + view = world.scene.add(lazy.isaacsim.core.prims.RigidPrim("/World/Objects/.*", name="my_object")) else: - view: Articulation = world.scene.add(Articulation("/World/Robot", name="my_object")) + view = world.scene.add(lazy.isaacsim.core.prims.Articulation("/World/Robot", name="my_object")) # Play simulator world.reset() # Get initial state diff --git a/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py b/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py index 7d89b3e793a..11300629c62 100644 --- a/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py +++ b/source/isaaclab/test/deps/isaacsim/check_floating_base_made_fixed.py @@ -9,12 +9,8 @@ import argparse -import contextlib -with contextlib.suppress(ModuleNotFoundError): - import isaacsim # noqa: F401 - -from isaacsim import SimulationApp +from isaaclab import lazy # add argparse arguments parser = argparse.ArgumentParser( @@ -26,26 +22,25 @@ args_cli = parser.parse_args() # launch omniverse app -simulation_app = SimulationApp({"headless": args_cli.headless}) +simulation_app = lazy.isaacsim.SimulationApp({"headless": args_cli.headless}) """Rest everything follows.""" import logging import torch -import isaacsim.core.utils.prims as prim_utils import omni.kit.commands import omni.physx -from isaacsim.core.api.world import World -from isaacsim.core.prims import Articulation -from isaacsim.core.utils.viewports import set_camera_view from pxr import PhysxSchema, UsdPhysics -# import logger -logger = logging.getLogger(__name__) import isaaclab.sim.utils.nucleus as nucleus_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.sim.utils.stage as stage_utils +# import logger +logger = logging.getLogger(__name__) + + # check nucleus connection if nucleus_utils.get_assets_root_path() is None: msg = ( @@ -71,9 +66,9 @@ def main(): """Spawns the ANYmal robot and makes it fixed.""" # Load kit helper - world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu") + world = lazy.isaacsim.core.api.world.World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu") # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) + lazy.isaacsim.core.utils.viewports.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Enable hydra scene-graph instancing # this is needed to visualize the scene when flatcache is enabled @@ -148,7 +143,7 @@ def main(): root_prim_path = parent_prim.GetPath().pathString # Setup robot - robot_view = Articulation(root_prim_path, name="ANYMAL") + robot_view = lazy.isaacsim.core.prims.Articulation(root_prim_path, name="ANYMAL") world.scene.add(robot_view) # Play the simulator world.reset() diff --git a/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py b/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py index 1085938c4fb..f1efe4f3766 100644 --- a/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py +++ b/source/isaaclab/test/deps/isaacsim/check_legged_robot_clone.py @@ -13,12 +13,8 @@ import argparse -import contextlib -with contextlib.suppress(ModuleNotFoundError): - import isaacsim # noqa: F401 - -from isaacsim import SimulationApp +from isaaclab import lazy # add argparse arguments parser = argparse.ArgumentParser( @@ -36,7 +32,7 @@ args_cli = parser.parse_args() # launch omniverse app -simulation_app = SimulationApp({"headless": args_cli.headless}) +simulation_app = lazy.isaacsim.SimulationApp({"headless": args_cli.headless}) """Rest everything follows.""" @@ -44,15 +40,11 @@ import os import torch -import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.world import World -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import Articulation -from isaacsim.core.utils.viewports import set_camera_view +import isaaclab.sim.utils.nucleus as nucleus_utils +import isaaclab.sim.utils.prims as prim_utils # import logger logger = logging.getLogger(__name__) -import isaaclab.sim.utils.nucleus as nucleus_utils # check nucleus connection if nucleus_utils.get_assets_root_path() is None: @@ -80,16 +72,16 @@ def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" # Load kit helper - world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0") + world = lazy.isaacsim.core.api.world.World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0") # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) + lazy.isaacsim.core.utils.viewports.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Enable hydra scene-graph instancing # this is needed to visualize the scene when flatcache is enabled world._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") # Everything under the namespace "/World/envs/env_0" will be cloned prim_utils.define_prim("/World/envs/env_0") @@ -147,7 +139,7 @@ def main(): else: raise ValueError(f"Invalid asset: {args_cli.asset}. Must be one of: isaaclab, oige.") # Setup robot - robot_view = Articulation(root_prim_path, name="ANYMAL") + robot_view = lazy.isaacsim.core.prims.Articulation(root_prim_path, name="ANYMAL") world.scene.add(robot_view) # Play the simulator world.reset() diff --git a/source/isaaclab/test/deps/isaacsim/check_ref_count.py b/source/isaaclab/test/deps/isaacsim/check_ref_count.py index 0cd579b559b..ee450a2397d 100644 --- a/source/isaaclab/test/deps/isaacsim/check_ref_count.py +++ b/source/isaaclab/test/deps/isaacsim/check_ref_count.py @@ -21,15 +21,10 @@ """Launch Isaac Sim Simulator first.""" -import contextlib - -with contextlib.suppress(ModuleNotFoundError): - import isaacsim # noqa: F401 - -from isaacsim import SimulationApp +from isaaclab import lazy # launch omniverse app -simulation_app = SimulationApp({"headless": True}) +simulation_app = lazy.isaacsim.SimulationApp({"headless": True}) """Rest everything follows.""" @@ -38,13 +33,12 @@ import logging import torch # noqa: F401 -import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.prims import Articulation +import isaaclab.sim.utils.nucleus as nucleus_utils +import isaaclab.sim.utils.prims as prim_utils # import logger logger = logging.getLogger(__name__) -import isaaclab.sim.utils.nucleus as nucleus_utils + # check nucleus connection if nucleus_utils.get_assets_root_path() is None: @@ -82,7 +76,7 @@ def __init__(self): # Resolve robot prim paths root_prim_path = "/World/Robot/base" # Setup robot - self.view = Articulation(root_prim_path, name="ANYMAL") + self.view = lazy.isaacsim.core.prims.Articulation(root_prim_path, name="ANYMAL") def __del__(self): """Delete the Anymal articulation class.""" @@ -103,7 +97,9 @@ def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" # Load kit helper - sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( + physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0" + ) # Enable hydra scene-graph instancing # this is needed to visualize the scene when flatcache is enabled diff --git a/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py b/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py index 5700b5c9044..bac7dfd8fec 100644 --- a/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py +++ b/source/isaaclab/test/deps/isaacsim/check_rep_texture_randomizer.py @@ -23,6 +23,8 @@ import argparse +from isaaclab import lazy + # isaaclab from isaaclab.app import AppLauncher @@ -45,13 +47,9 @@ import numpy as np import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.objects import DynamicSphere -from isaacsim.core.prims import RigidPrim -from isaacsim.core.utils.viewports import set_camera_view + +import isaaclab.sim.utils.prims as prim_utils def main(): @@ -65,24 +63,26 @@ def main(): "use_fabric": True, # used from Isaac Sim 2023.1 onwards "enable_scene_query_support": True, } - sim = SimulationContext( + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( physics_dt=1.0 / 60.0, rendering_dt=1.0 / 60.0, sim_params=sim_params, backend="torch", device="cuda:0" ) # Set main camera - set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) + lazy.isaacsim.core.utils.viewports.set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) # Parameters num_balls = 128 # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") # Everything under the namespace "/World/envs/env_0" will be cloned prim_utils.define_prim("/World/envs/env_0") # Define the scene # -- Ball - DynamicSphere(prim_path="/World/envs/env_0/ball", translation=np.array([0.0, 0.0, 5.0]), mass=0.5, radius=0.25) + lazy.isaacsim.core.objects.DynamicSphere( + prim_path="/World/envs/env_0/ball", translation=np.array([0.0, 0.0, 5.0]), mass=0.5, radius=0.25 + ) # Clone the scene cloner.define_base_env("/World/envs") @@ -112,7 +112,7 @@ def get_shapes(): # Set ball positions over terrain origins # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + ball_view = lazy.isaacsim.core.prims.RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) # cache initial state of the balls ball_initial_positions = torch.tensor(env_positions, dtype=torch.float, device=sim.device) ball_initial_positions[:, 2] += 5.0 diff --git a/source/isaaclab/test/devices/check_keyboard.py b/source/isaaclab/test/devices/check_keyboard.py index 711423d3e5e..7243c20d7e3 100644 --- a/source/isaaclab/test/devices/check_keyboard.py +++ b/source/isaaclab/test/devices/check_keyboard.py @@ -13,6 +13,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -23,8 +24,6 @@ import ctypes -from isaacsim.core.api.simulation_context import SimulationContext - from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg @@ -41,7 +40,7 @@ def quit_cb(): def main(): # Load kit helper - sim = SimulationContext(physics_dt=0.01, rendering_dt=0.01) + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=0.01, rendering_dt=0.01) # Create teleoperation interface teleop_interface = Se3Keyboard(Se3KeyboardCfg(pos_sensitivity=0.1, rot_sensitivity=0.1)) diff --git a/source/isaaclab/test/devices/test_oxr_device.py b/source/isaaclab/test/devices/test_oxr_device.py index 7512333d80c..ebe0caa0c1c 100644 --- a/source/isaaclab/test/devices/test_oxr_device.py +++ b/source/isaaclab/test/devices/test_oxr_device.py @@ -8,6 +8,7 @@ from __future__ import annotations +from isaaclab import lazy from isaaclab.app import AppLauncher # Can set this to False to see the GUI for debugging. @@ -24,7 +25,6 @@ import carb import omni.usd import pytest -from isaacsim.core.prims import XFormPrim from isaaclab.devices import OpenXRDevice, OpenXRDeviceCfg from isaaclab.devices.openxr import XrCfg @@ -179,7 +179,7 @@ def test_xr_anchor(empty_env, mock_xrcore): device = OpenXRDevice(OpenXRDeviceCfg(xr_cfg=env_cfg.xr)) # Check that the xr anchor prim is created with the correct pose - xr_anchor_prim = XFormPrim("/World/XRAnchor") + xr_anchor_prim = lazy.isaacsim.core.prims.xform_prim.XFormPrim("/XRAnchor") assert xr_anchor_prim.is_valid() position, orientation = xr_anchor_prim.get_world_poses() @@ -201,7 +201,7 @@ def test_xr_anchor_default(empty_env, mock_xrcore): device = OpenXRDevice(OpenXRDeviceCfg()) # Check that the xr anchor prim is created with the correct default pose - xr_anchor_prim = XFormPrim("/World/XRAnchor") + xr_anchor_prim = lazy.isaacsim.core.prims.xform_prim.XFormPrim("/XRAnchor") assert xr_anchor_prim.is_valid() position, orientation = xr_anchor_prim.get_world_poses() @@ -224,7 +224,7 @@ def test_xr_anchor_multiple_devices(empty_env, mock_xrcore): device_2 = OpenXRDevice(OpenXRDeviceCfg()) # Check that the xr anchor prim is created with the correct default pose - xr_anchor_prim = XFormPrim("/World/XRAnchor") + xr_anchor_prim = lazy.isaacsim.core.prims.xform_prim.XFormPrim("/XRAnchor") assert xr_anchor_prim.is_valid() position, orientation = xr_anchor_prim.get_world_poses() diff --git a/source/isaaclab/test/envs/test_color_randomization.py b/source/isaaclab/test/envs/test_color_randomization.py index a550e773337..fadc258dfb9 100644 --- a/source/isaaclab/test/envs/test_color_randomization.py +++ b/source/isaaclab/test/envs/test_color_randomization.py @@ -9,6 +9,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -22,7 +23,6 @@ import omni.usd import pytest -from isaacsim.core.version import get_version import isaaclab.envs.mdp as mdp from isaaclab.envs import ManagerBasedEnv, ManagerBasedEnvCfg @@ -138,7 +138,7 @@ def __post_init__(self): def test_color_randomization(device): """Test color randomization for cartpole environment.""" # skip test if stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: pytest.skip("Color randomization test hangs in this version of Isaac Sim") diff --git a/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py b/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py index e3c26a86b42..9a03baa021c 100644 --- a/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py +++ b/source/isaaclab/test/envs/test_manager_based_rl_env_ui.py @@ -10,6 +10,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher simulation_app = AppLauncher(headless=True, enable_cameras=True).app @@ -18,14 +19,13 @@ import carb import omni.usd -from isaacsim.core.utils.extensions import enable_extension from isaaclab.envs import ManagerBasedRLEnv, ManagerBasedRLEnvCfg from isaaclab.envs.ui import ManagerBasedRLEnvWindow from isaaclab.scene import InteractiveSceneCfg from isaaclab.utils import configclass -enable_extension("isaacsim.gui.components") +lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.gui.components") @configclass diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index f6a41a6dcb8..a927c59af96 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -15,12 +16,11 @@ import torch import pytest -from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg from isaaclab.markers.config import FRAME_MARKER_CFG, POSITION_GOAL_MARKER_CFG -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.math import random_orientation from isaaclab.utils.timer import Timer @@ -33,7 +33,9 @@ def sim(): # Open a new stage stage_utils.create_new_stage() # Load kit helper - sim_context = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="torch", device="cuda:0") + sim_context = lazy.isaacsim.core.api.simulation_context.SimulationContext( + physics_dt=dt, rendering_dt=dt, backend="torch", device="cuda:0" + ) yield sim_context # Cleanup sim_context.stop() diff --git a/source/isaaclab/test/performance/test_robot_load_performance.py b/source/isaaclab/test/performance/test_robot_load_performance.py index bca8c36d9d5..4ade0a87bac 100644 --- a/source/isaaclab/test/performance/test_robot_load_performance.py +++ b/source/isaaclab/test/performance/test_robot_load_performance.py @@ -8,6 +8,7 @@ from __future__ import annotations +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -15,7 +16,6 @@ import omni import pytest -from isaacsim.core.cloner import GridCloner from isaaclab_assets import ANYMAL_D_CFG, CARTPOLE_CFG @@ -37,7 +37,7 @@ def test_robot_load_performance(test_config, device): """Test robot load time.""" with build_simulation_context(device=device) as sim: sim._app_control_on_stop_handle = None - cloner = GridCloner(spacing=2) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2) target_paths = cloner.generate_paths("/World/Robots", 4096) omni.usd.get_context().get_stage().DefinePrim(target_paths[0], "Xform") _ = cloner.clone( diff --git a/source/isaaclab/test/sensors/check_contact_sensor.py b/source/isaaclab/test/sensors/check_contact_sensor.py index 190e94ebe78..04e4fdc03a1 100644 --- a/source/isaaclab/test/sensors/check_contact_sensor.py +++ b/source/isaaclab/test/sensors/check_contact_sensor.py @@ -16,6 +16,7 @@ import argparse +from isaaclab import lazy from isaaclab.app import AppLauncher # add argparse arguments @@ -36,12 +37,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.utils.viewports import set_camera_view - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils from isaaclab.assets import Articulation from isaaclab.sensors.contact_sensor import ContactSensor, ContactSensorCfg from isaaclab.utils.timer import Timer @@ -76,16 +73,18 @@ def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" # Load kit helper - sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( + physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda:0" + ) # Set main camera - set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) + lazy.isaacsim.core.utils.viewports.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) # Enable hydra scene-graph instancing # this is needed to visualize the scene when flatcache is enabled sim._settings.set_bool("/persistent/omnihydra/useSceneGraphInstancing", True) # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") # Everything under the namespace "/World/envs/env_0" will be cloned prim_utils.define_prim("/World/envs/env_0") diff --git a/source/isaaclab/test/sensors/check_imu_sensor.py b/source/isaaclab/test/sensors/check_imu_sensor.py index 652e2d95073..29c08186214 100644 --- a/source/isaaclab/test/sensors/check_imu_sensor.py +++ b/source/isaaclab/test/sensors/check_imu_sensor.py @@ -13,7 +13,7 @@ import argparse -from isaacsim import SimulationApp +from isaaclab import lazy # add argparse arguments parser = argparse.ArgumentParser(description="Imu Test Script") @@ -30,7 +30,7 @@ # launch omniverse app config = {"headless": args_cli.headless} -simulation_app = SimulationApp(config) +simulation_app = lazy.isaacsim.SimulationApp(config) """Rest everything follows.""" @@ -40,9 +40,6 @@ import carb import omni -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.utils.viewports import set_camera_view from pxr import PhysxSchema import isaaclab.sim as sim_utils @@ -55,7 +52,7 @@ from isaaclab.utils.timer import Timer -def design_scene(sim: SimulationContext, num_envs: int = 2048) -> RigidObject: +def design_scene(sim, num_envs: int = 2048) -> RigidObject: """Design the scene.""" # Handler for terrains importing terrain_importer_cfg = terrain_gen.TerrainImporterCfg( @@ -70,7 +67,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048) -> RigidObject: # obtain the current stage stage = omni.usd.get_context().get_stage() # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) # create source prim @@ -122,11 +119,11 @@ def main(): "use_fabric": True, # used from Isaac Sim 2023.1 onwards "enable_scene_query_support": True, } - sim = SimulationContext( + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( physics_dt=1.0 / 60.0, rendering_dt=1.0 / 60.0, sim_params=sim_params, backend="torch", device="cuda:0" ) # Set main camera - set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) + lazy.isaacsim.core.utils.viewports.set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) # Parameters num_envs = args_cli.num_envs diff --git a/source/isaaclab/test/sensors/check_ray_caster.py b/source/isaaclab/test/sensors/check_ray_caster.py index e1d3473ecc4..29adbfbc069 100644 --- a/source/isaaclab/test/sensors/check_ray_caster.py +++ b/source/isaaclab/test/sensors/check_ray_caster.py @@ -16,6 +16,7 @@ import argparse +from isaaclab import lazy from isaaclab.app import AppLauncher # add argparse arguments @@ -41,13 +42,8 @@ import torch -import isaacsim.core.utils.prims as prim_utils -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import RigidPrim -from isaacsim.core.utils.viewports import set_camera_view - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.terrains as terrain_gen from isaaclab.sensors.ray_caster import RayCaster, RayCasterCfg, patterns from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG @@ -56,10 +52,10 @@ from isaaclab.utils.timer import Timer -def design_scene(sim: SimulationContext, num_envs: int = 2048): +def design_scene(sim, num_envs: int = 2048): """Design the scene.""" # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") # Everything under the namespace "/World/envs/env_0" will be cloned prim_utils.define_prim("/World/envs/env_0") @@ -97,11 +93,11 @@ def main(): "use_fabric": True, # used from Isaac Sim 2023.1 onwards "enable_scene_query_support": True, } - sim = SimulationContext( + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( physics_dt=1.0 / 60.0, rendering_dt=1.0 / 60.0, sim_params=sim_params, backend="torch", device="cuda:0" ) # Set main camera - set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) + lazy.isaacsim.core.utils.viewports.set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) # Parameters num_envs = args_cli.num_envs @@ -128,7 +124,7 @@ def main(): ) ray_caster = RayCaster(cfg=ray_caster_cfg) # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + ball_view = lazy.isaacsim.core.prims.RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) # Play simulator sim.reset() diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index c6775606a0b..74c01193b68 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -8,6 +8,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -22,15 +23,14 @@ import scipy.spatial.transform as tf import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep import pytest -from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, Usd, UsdGeom import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors.camera import Camera, CameraCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils import convert_dict_to_backend from isaaclab.utils.math import convert_quat from isaaclab.utils.timer import Timer @@ -905,5 +905,5 @@ def _populate_scene(): geom_prim.CreateDisplayColorAttr() geom_prim.GetDisplayColorAttr().Set([color]) # add rigid properties - SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) - SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) + lazy.isaacsim.core.prims.SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) + lazy.isaacsim.core.prims.SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) diff --git a/source/isaaclab/test/sensors/test_contact_sensor.py b/source/isaaclab/test/sensors/test_contact_sensor.py index ac70e8b7659..c6fef707539 100644 --- a/source/isaaclab/test/sensors/test_contact_sensor.py +++ b/source/isaaclab/test/sensors/test_contact_sensor.py @@ -28,6 +28,7 @@ from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import ContactSensor, ContactSensorCfg from isaaclab.sim import SimulationContext, build_simulation_context +from isaaclab.sim.utils.stage import get_current_stage from isaaclab.terrains import HfRandomUniformTerrainCfg, TerrainGeneratorCfg, TerrainImporterCfg from isaaclab.utils import configclass @@ -418,9 +419,6 @@ def test_contact_sensor_threshold(setup_simulation, device): # Play the simulator sim.reset() - # Get the stage and check the USD threshold attribute on the rigid body prim - from isaacsim.core.utils.stage import get_current_stage - stage = get_current_stage() prim_path = scene_cfg.shape.prim_path prim = stage.GetPrimAtPath(prim_path) diff --git a/source/isaaclab/test/sensors/test_frame_transformer.py b/source/isaaclab/test/sensors/test_frame_transformer.py index 47405b15768..5257e732420 100644 --- a/source/isaaclab/test/sensors/test_frame_transformer.py +++ b/source/isaaclab/test/sensors/test_frame_transformer.py @@ -19,11 +19,11 @@ import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.assets import RigidObjectCfg from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors import FrameTransformerCfg, OffsetCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass diff --git a/source/isaaclab/test/sensors/test_imu.py b/source/isaaclab/test/sensors/test_imu.py index a7bdafb6dbd..d8074e36234 100644 --- a/source/isaaclab/test/sensors/test_imu.py +++ b/source/isaaclab/test/sensors/test_imu.py @@ -20,13 +20,13 @@ import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.markers.config import GREEN_ARROW_X_MARKER_CFG, RED_ARROW_X_MARKER_CFG from isaaclab.scene import InteractiveScene, InteractiveSceneCfg from isaaclab.sensors.imu import ImuCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index e458b3db777..16b897a3b6b 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -8,6 +8,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -20,16 +21,15 @@ import random import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep import pytest from flaky import flaky -from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors.camera import TiledCamera, TiledCameraCfg -from isaaclab.sim.utils import stage as stage_utils @pytest.fixture() @@ -505,5 +505,5 @@ def _populate_scene(): geom_prim.CreateDisplayColorAttr() geom_prim.GetDisplayColorAttr().Set([color]) # add rigid properties - SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) - SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) + lazy.isaacsim.core.prims.SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) + lazy.isaacsim.core.prims.SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index e483a6bd4e6..9c549fdcabd 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -20,16 +20,16 @@ import os import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep import pytest from pxr import Gf import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors.camera import Camera, CameraCfg from isaaclab.sensors.ray_caster import RayCasterCamera, RayCasterCameraCfg, patterns from isaaclab.sim import PinholeCameraCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.terrains.trimesh.utils import make_plane from isaaclab.terrains.utils import create_prim_from_mesh from isaaclab.utils import convert_dict_to_backend diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 86e63e59865..13af8286193 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -18,12 +18,12 @@ from collections.abc import Sequence from dataclasses import dataclass -import isaacsim.core.utils.prims as prim_utils import pytest import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sensors import SensorBase, SensorBaseCfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils import configclass diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 7eb36fbcb7e..95186e32176 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -8,6 +8,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -20,13 +21,12 @@ import random import torch -import isaacsim.core.utils.prims as prim_utils import omni.replicator.core as rep import pytest -from isaacsim.core.prims import SingleGeometryPrim, SingleRigidPrim from pxr import Gf, UsdGeom -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils # from Isaac Sim 4.2 onwards, pxr.Semantics is deprecated try: @@ -1768,5 +1768,5 @@ def _populate_scene(): geom_prim.CreateDisplayColorAttr() geom_prim.GetDisplayColorAttr().Set([color]) # add rigid properties - SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) - SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) + lazy.isaacsim.core.prims.SingleGeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True) + lazy.isaacsim.core.prims.SingleRigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0) diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index 8595605b747..ecee0f07121 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -40,9 +40,8 @@ import torch import tqdm -import isaacsim.core.utils.prims as prim_utils - import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils def define_origins(num_origins: int, spacing: float) -> list[list[float]]: diff --git a/source/isaaclab/test/sim/test_build_simulation_context_headless.py b/source/isaaclab/test/sim/test_build_simulation_context_headless.py index af29346f9ee..44f101e58ed 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.py @@ -21,8 +21,8 @@ """Rest everything follows.""" import pytest -from isaacsim.core.utils.prims import is_prim_path_valid +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim.simulation_cfg import SimulationCfg from isaaclab.sim.simulation_context import build_simulation_context @@ -43,7 +43,7 @@ def test_build_simulation_context_no_cfg(gravity_enabled, device, dt): assert sim.cfg.dt == dt # Ensure that dome light didn't get added automatically as we are headless - assert not is_prim_path_valid("/World/defaultDomeLight") + assert not prim_utils.is_prim_path_valid("/World/defaultDomeLight") @pytest.mark.parametrize("add_ground_plane", [True, False]) @@ -52,7 +52,7 @@ def test_build_simulation_context_ground_plane(add_ground_plane): """Test that the simulation context is built with the correct ground plane.""" with build_simulation_context(add_ground_plane=add_ground_plane) as _: # Ensure that ground plane got added - assert is_prim_path_valid("/World/defaultGroundPlane") == add_ground_plane + assert prim_utils.is_prim_path_valid("/World/defaultGroundPlane") == add_ground_plane @pytest.mark.parametrize("add_lighting", [True, False]) @@ -63,10 +63,10 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light with build_simulation_context(add_lighting=add_lighting, auto_add_lighting=auto_add_lighting) as _: if add_lighting: # Ensure that dome light got added - assert is_prim_path_valid("/World/defaultDomeLight") + assert prim_utils.is_prim_path_valid("/World/defaultDomeLight") else: # Ensure that dome light didn't get added as there's no GUI - assert not is_prim_path_valid("/World/defaultDomeLight") + assert not prim_utils.is_prim_path_valid("/World/defaultDomeLight") @pytest.mark.isaacsim_ci diff --git a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py index 1c1bf480da4..a7ed9b2f89e 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -12,6 +12,7 @@ """Launch Isaac Sim Simulator first.""" + from isaaclab.app import AppLauncher # launch omniverse app @@ -20,8 +21,8 @@ """Rest everything follows.""" import pytest -from isaacsim.core.utils.prims import is_prim_path_valid +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim.simulation_cfg import SimulationCfg from isaaclab.sim.simulation_context import build_simulation_context @@ -46,7 +47,7 @@ def test_build_simulation_context_ground_plane(add_ground_plane): """Test that the simulation context is built with the correct ground plane.""" with build_simulation_context(add_ground_plane=add_ground_plane) as _: # Ensure that ground plane got added - assert is_prim_path_valid("/World/defaultGroundPlane") == add_ground_plane + assert prim_utils.is_prim_path_valid("/World/defaultGroundPlane") == add_ground_plane @pytest.mark.parametrize("add_lighting", [True, False]) @@ -56,10 +57,10 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light with build_simulation_context(add_lighting=add_lighting, auto_add_lighting=auto_add_lighting) as _: if auto_add_lighting or add_lighting: # Ensure that dome light got added - assert is_prim_path_valid("/World/defaultDomeLight") + assert prim_utils.is_prim_path_valid("/World/defaultDomeLight") else: # Ensure that dome light didn't get added - assert not is_prim_path_valid("/World/defaultDomeLight") + assert not prim_utils.is_prim_path_valid("/World/defaultDomeLight") def test_build_simulation_context_cfg(): diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index 761d5bfa0a6..3fbfb83b1c9 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -17,15 +18,14 @@ import random import tempfile -import isaacsim.core.utils.prims as prim_utils import omni import pytest -from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdGeom, UsdPhysics +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import MeshConverter, MeshConverterCfg from isaaclab.sim.schemas import schemas_cfg -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR, retrieve_file_path @@ -66,7 +66,7 @@ def sim(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") yield sim # stop simulation sim.stop() @@ -98,12 +98,12 @@ def check_mesh_conversion(mesh_converter: MeshConverter): assert units == 1.0 # Check mesh settings - pos = tuple(prim_utils.get_prim_at_path("/World/Object/geometry").GetAttribute("xformOp:translate").Get()) + pos = prim_utils.get_prim_at_path("/World/Object/geometry").GetAttribute("xformOp:translate").Get() assert pos == mesh_converter.cfg.translation quat = prim_utils.get_prim_at_path("/World/Object/geometry").GetAttribute("xformOp:orient").Get() quat = (quat.GetReal(), quat.GetImaginary()[0], quat.GetImaginary()[1], quat.GetImaginary()[2]) assert quat == mesh_converter.cfg.rotation - scale = tuple(prim_utils.get_prim_at_path("/World/Object/geometry").GetAttribute("xformOp:scale").Get()) + scale = prim_utils.get_prim_at_path("/World/Object/geometry").GetAttribute("xformOp:scale").Get() assert scale == mesh_converter.cfg.scale diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 8160d12d4ce..f53ae431e5a 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -14,13 +15,11 @@ import os -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import MjcfConverter, MjcfConverterCfg -from isaaclab.sim.utils import stage as stage_utils @pytest.fixture(autouse=True) @@ -31,11 +30,11 @@ def test_setup_teardown(): # Setup: Create simulation context dt = 0.01 - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") # Setup: Create MJCF config - enable_extension("isaacsim.asset.importer.mjcf") - extension_path = get_extension_path_from_name("isaacsim.asset.importer.mjcf") + lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.asset.importer.mjcf") + extension_path = lazy.isaacsim.core.utils.extensions.get_extension_path_from_name("isaacsim.asset.importer.mjcf") config = MjcfConverterCfg( asset_path=f"{extension_path}/data/mjcf/nv_ant.xml", import_sites=True, diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index aef0703c820..3867b128216 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -14,14 +15,13 @@ import math -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdPhysics import isaaclab.sim.schemas as schemas +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.utils import find_global_fixed_joint_prim -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.string import to_camel_case @@ -34,7 +34,7 @@ def setup_simulation(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") # Set some default values for test arti_cfg = schemas.ArticulationRootPropertiesCfg( enabled_self_collisions=False, diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index f0f783463d2..268ad26b09d 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -14,10 +15,9 @@ import numpy as np -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext as IsaacSimulationContext +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -39,7 +39,7 @@ def test_singleton(): """Tests that the singleton is working.""" sim1 = SimulationContext() sim2 = SimulationContext() - sim3 = IsaacSimulationContext() + sim3 = lazy.isaacsim.core.api.simulation_context.SimulationContext() assert sim1 is sim2 assert sim1 is sim3 diff --git a/source/isaaclab/test/sim/test_simulation_render_config.py b/source/isaaclab/test/sim/test_simulation_render_config.py index 650cff46765..9b4350a70ac 100644 --- a/source/isaaclab/test/sim/test_simulation_render_config.py +++ b/source/isaaclab/test/sim/test_simulation_render_config.py @@ -6,6 +6,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -20,7 +21,6 @@ import carb import flatdict import pytest -from isaacsim.core.version import get_version from isaaclab.sim.simulation_cfg import RenderCfg, SimulationCfg from isaaclab.sim.simulation_context import SimulationContext @@ -107,7 +107,7 @@ def test_render_cfg_presets(): # grab isaac lab apps path isaaclab_app_exp_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), *[".."] * 4, "apps") # for Isaac Sim 4.5 compatibility, we use the 4.5 rendering mode app files in a different folder - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: isaaclab_app_exp_path = os.path.join(isaaclab_app_exp_path, "isaacsim_4_5") diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index 5da16d81f5e..c267f2e6b54 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -3,6 +3,7 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab import lazy from isaaclab.app import AppLauncher """Launch Isaac Sim Simulator first.""" @@ -12,13 +13,11 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name import isaaclab.sim as sim_utils -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -30,7 +29,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") # Wait for spawning stage_utils.update_stage() @@ -69,8 +68,8 @@ def test_spawn_usd_fails(sim): def test_spawn_urdf(sim): """Test loading prim from URDF file.""" # retrieve path to urdf importer extension - enable_extension("isaacsim.asset.importer.urdf") - extension_path = get_extension_path_from_name("isaacsim.asset.importer.urdf") + lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.asset.importer.urdf") + extension_path = lazy.isaacsim.core.utils.extensions.get_extension_path_from_name("isaacsim.asset.importer.urdf") # Spawn franka from URDF cfg = sim_utils.UrdfFileCfg( asset_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index ee8446188cd..7fcf97145dc 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,13 +13,12 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdLux import isaaclab.sim as sim_utils -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.string import to_camel_case @@ -30,7 +30,7 @@ def test_setup_teardown(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") # Wait for spawning stage_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index df2a5778831..65db537461b 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,13 +13,12 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext from pxr import UsdPhysics, UsdShade import isaaclab.sim as sim_utils -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.assets import NVIDIA_NUCLEUS_DIR @@ -27,7 +27,7 @@ def sim(): """Create a simulation context.""" stage_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") stage_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index bc65bb4923b..509e1e64830 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,12 +13,11 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils @pytest.fixture @@ -28,7 +28,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, device="cuda:0") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, device="cuda:0") # Wait for spawning stage_utils.update_stage() yield sim diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index 8896d669b31..6919f2d8028 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,13 +13,12 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext 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.sensors.sensors import CUSTOM_FISHEYE_CAMERA_ATTRIBUTES, CUSTOM_PINHOLE_CAMERA_ATTRIBUTES -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.string import to_camel_case @@ -27,7 +27,7 @@ def sim(): """Create a simulation context.""" stage_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") stage_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_spawn_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index 970be4a47f9..ab395ede77b 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,12 +13,11 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils @pytest.fixture @@ -25,7 +25,7 @@ def sim(): """Create a simulation context.""" stage_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") stage_utils.update_stage() yield sim sim.stop() @@ -259,7 +259,7 @@ def test_spawn_cone_clones(sim): assert prim.IsValid() assert prim_utils.get_prim_path(prim) == "/World/env_0/Cone" # find matching prims - prims = prim_utils.find_matching_prim_paths("/World/env_*/Cone") + prims = sim_utils.find_matching_prim_paths("/World/env_.*/Cone") assert len(prims) == num_clones @@ -285,8 +285,8 @@ def test_spawn_cone_clone_with_all_props_global_material(sim): assert prim.IsValid() assert prim_utils.get_prim_path(prim) == "/World/env_0/Cone" # find matching prims - prims = prim_utils.find_matching_prim_paths("/World/env_*/Cone") + prims = sim_utils.find_matching_prim_paths("/World/env_.*/Cone") assert len(prims) == num_clones # find matching material prims - prims = prim_utils.find_matching_prim_paths("/Looks/visualMaterial.*") + prims = sim_utils.find_matching_prim_paths("/Looks/visualMaterial.*") assert len(prims) == 1 diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 2449cd5ad85..9dffd0f16f3 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,12 +13,11 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext import isaaclab.sim as sim_utils -from isaaclab.sim.utils import stage as stage_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -26,7 +26,7 @@ def sim(): """Create a simulation context.""" stage_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext(physics_dt=dt, rendering_dt=dt, backend="numpy") stage_utils.update_stage() yield sim sim.stop() @@ -69,7 +69,7 @@ def test_spawn_multiple_shapes_with_global_settings(sim): assert prim.IsValid() assert prim_utils.get_prim_path(prim) == "/World/env_0/Cone" - prim_paths = prim_utils.find_matching_prim_paths("/World/env_*/Cone") + prim_paths = sim_utils.find_matching_prim_paths("/World/env_.*/Cone") assert len(prim_paths) == num_clones for prim_path in prim_paths: @@ -115,7 +115,7 @@ def test_spawn_multiple_shapes_with_individual_settings(sim): assert prim.IsValid() assert prim_utils.get_prim_path(prim) == "/World/env_0/Cone" - prim_paths = prim_utils.find_matching_prim_paths("/World/env_*/Cone") + prim_paths = sim_utils.find_matching_prim_paths("/World/env_.*/Cone") assert len(prim_paths) == num_clones for prim_path in prim_paths: @@ -158,5 +158,5 @@ def test_spawn_multiple_files_with_global_settings(sim): assert prim.IsValid() assert prim_utils.get_prim_path(prim) == "/World/env_0/Robot" - prim_paths = prim_utils.find_matching_prim_paths("/World/env_*/Robot") + prim_paths = sim_utils.find_matching_prim_paths("/World/env_.*/Robot") assert len(prim_paths) == num_clones diff --git a/source/isaaclab/test/sim/test_stage_in_memory.py b/source/isaaclab/test/sim/test_stage_in_memory.py index 2910a4fe290..0eb43196b49 100644 --- a/source/isaaclab/test/sim/test_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_stage_in_memory.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -12,18 +13,16 @@ """Rest everything follows.""" -import isaacsim.core.utils.prims as prim_utils import omni import omni.physx import omni.usd import pytest import usdrt -from isaacsim.core.cloner import GridCloner -from isaacsim.core.version import get_version 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.simulation_context import SimulationCfg, SimulationContext -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -50,7 +49,7 @@ def test_stage_in_memory_with_shapes(sim): """Test spawning of shapes with stage in memory.""" # skip test if stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: pytest.skip("Stage in memory is not supported in this version of Isaac Sim") @@ -115,7 +114,7 @@ def test_stage_in_memory_with_usds(sim): """Test spawning of USDs with stage in memory.""" # skip test if stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: pytest.skip("Stage in memory is not supported in this version of Isaac Sim") @@ -181,7 +180,7 @@ def test_stage_in_memory_with_clone_in_fabric(sim): """Test cloning in fabric with stage in memory.""" # skip test if stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: pytest.skip("Stage in memory is not supported in this version of Isaac Sim") @@ -197,7 +196,7 @@ def test_stage_in_memory_with_clone_in_fabric(sim): source_prim_path = f"{base_env_path}/env_0" # create cloner - cloner = GridCloner(spacing=3, stage=stage_in_memory) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=3, stage=stage_in_memory) cloner.define_base_env(base_env_path) # create source prim diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 15ba6d66b3c..47b8828ceb8 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -5,6 +5,7 @@ """Launch Isaac Sim Simulator first.""" +from isaaclab import lazy from isaaclab.app import AppLauncher # launch omniverse app @@ -15,14 +16,11 @@ import numpy as np import os -import isaacsim.core.utils.prims as prim_utils import pytest -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.prims import Articulation -from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg -from isaaclab.sim.utils import stage as stage_utils # Create a fixture for setup and teardown @@ -31,8 +29,8 @@ def sim_config(): # Create a new stage stage_utils.create_new_stage() # retrieve path to urdf importer extension - enable_extension("isaacsim.asset.importer.urdf") - extension_path = get_extension_path_from_name("isaacsim.asset.importer.urdf") + lazy.isaacsim.core.utils.extensions.enable_extension("isaacsim.asset.importer.urdf") + extension_path = lazy.isaacsim.core.utils.extensions.get_extension_path_from_name("isaacsim.asset.importer.urdf") # default configuration config = UrdfConverterCfg( asset_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", @@ -44,7 +42,9 @@ def sim_config(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(physics_dt=dt, rendering_dt=dt, stage_units_in_meters=1.0, backend="numpy") + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( + physics_dt=dt, rendering_dt=dt, stage_units_in_meters=1.0, backend="numpy" + ) yield sim, config # Teardown sim.stop() @@ -123,7 +123,7 @@ def test_config_drive_type(sim_config): prim_utils.create_prim(prim_path, usd_path=urdf_converter.usd_path) # access the robot - robot = Articulation(prim_path, reset_xform_properties=False) + robot = lazy.isaacsim.core.prims.Articulation(prim_path, reset_xform_properties=False) # play the simulator and initialize the robot sim.reset() robot.initialize() diff --git a/source/isaaclab/test/sim/test_utils.py b/source/isaaclab/test/sim/test_utils.py index 248785c77aa..5d2e29075fb 100644 --- a/source/isaaclab/test/sim/test_utils.py +++ b/source/isaaclab/test/sim/test_utils.py @@ -15,13 +15,13 @@ import numpy as np import torch -import isaacsim.core.utils.prims as prim_utils import pytest from pxr import Sdf, Usd, UsdGeom, UsdPhysics import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils +import isaaclab.sim.utils.stage as stage_utils import isaaclab.utils.math as math_utils -from isaaclab.sim.utils import stage as stage_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR @@ -104,36 +104,6 @@ def test_get_first_matching_child_prim(): assert isaaclab_result.GetPrimPath() == "/World/env_1/Franka/panda_link0/visuals/panda_link0" -def test_find_matching_prim_paths(): - """Test find_matching_prim_paths() function.""" - # create scene - for index in range(2048): - random_pos = np.random.uniform(-100, 100, size=3) - prim_utils.create_prim(f"/World/Floor_{index}", "Cube", position=random_pos, attributes={"size": 2.0}) - prim_utils.create_prim(f"/World/Floor_{index}/Sphere", "Sphere", attributes={"radius": 10}) - prim_utils.create_prim(f"/World/Floor_{index}/Sphere/childSphere", "Sphere", attributes={"radius": 1}) - prim_utils.create_prim(f"/World/Floor_{index}/Sphere/childSphere2", "Sphere", attributes={"radius": 1}) - - # test leaf paths - isaac_sim_result = prim_utils.find_matching_prim_paths("/World/Floor_.*/Sphere") - isaaclab_result = sim_utils.find_matching_prim_paths("/World/Floor_.*/Sphere") - assert isaac_sim_result == isaaclab_result - - # test non-leaf paths - isaac_sim_result = prim_utils.find_matching_prim_paths("/World/Floor_.*") - isaaclab_result = sim_utils.find_matching_prim_paths("/World/Floor_.*") - assert isaac_sim_result == isaaclab_result - - # test child-leaf paths - isaac_sim_result = prim_utils.find_matching_prim_paths("/World/Floor_.*/Sphere/childSphere.*") - isaaclab_result = sim_utils.find_matching_prim_paths("/World/Floor_.*/Sphere/childSphere.*") - assert isaac_sim_result == isaaclab_result - - # test valid path - with pytest.raises(ValueError): - sim_utils.get_all_matching_child_prims("World/Floor_.*") - - def test_find_global_fixed_joint_prim(): """Test find_global_fixed_joint_prim() function.""" # create scene diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index 2de8b457e32..95c1f88cbfa 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -30,6 +30,8 @@ import argparse +from isaaclab import lazy + # isaaclab from isaaclab.app import AppLauncher @@ -64,25 +66,17 @@ import numpy as np -import isaacsim.core.utils.prims as prim_utils import omni.kit import omni.kit.commands -from isaacsim.core.api.materials import PhysicsMaterial -from isaacsim.core.api.materials.preview_surface import PreviewSurface -from isaacsim.core.api.objects import DynamicSphere -from isaacsim.core.api.simulation_context import SimulationContext -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import RigidPrim, SingleGeometryPrim, SingleRigidPrim -from isaacsim.core.utils.extensions import enable_extension -from isaacsim.core.utils.viewports import set_camera_view import isaaclab.sim as sim_utils +import isaaclab.sim.utils.prims as prim_utils import isaaclab.terrains as terrain_gen from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG from isaaclab.terrains.terrain_importer import TerrainImporter from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -enable_extension("omni.kit.primitive.mesh") +lazy.isaacsim.core.utils.extensions.enable_extension("omni.kit.primitive.mesh") def main(): @@ -96,17 +90,17 @@ def main(): "use_fabric": True, "enable_scene_query_support": True, } - sim = SimulationContext( + sim = lazy.isaacsim.core.api.simulation_context.SimulationContext( physics_dt=1.0 / 60.0, rendering_dt=1.0 / 60.0, sim_params=sim_params, backend="torch", device="cuda:0" ) # Set main camera - set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) + lazy.isaacsim.core.utils.viewports.set_camera_view([0.0, 30.0, 25.0], [0.0, 0.0, -2.5]) # Parameters num_balls = 2048 # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") # Everything under the namespace "/World/envs/env_0" will be cloned prim_utils.define_prim("/World/envs/env_0") @@ -130,7 +124,7 @@ def main(): # -- Ball if args_cli.geom_sphere: # -- Ball physics - _ = DynamicSphere( + _ = lazy.isaacsim.core.objects.DynamicSphere( prim_path="/World/envs/env_0/ball", translation=np.array([0.0, 0.0, 5.0]), mass=0.5, radius=0.25 ) else: @@ -138,14 +132,16 @@ def main(): cube_prim_path = omni.kit.commands.execute("CreateMeshPrimCommand", prim_type="Sphere")[1] prim_utils.move_prim(cube_prim_path, "/World/envs/env_0/ball") # -- Ball physics - SingleRigidPrim( + lazy.isaacsim.core.prims.SingleRigidPrim( prim_path="/World/envs/env_0/ball", mass=0.5, scale=(0.5, 0.5, 0.5), translation=(0.0, 0.0, 0.5) ) - SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) + lazy.isaacsim.core.prims.SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) # -- Ball material - sphere_geom = SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) - visual_material = PreviewSurface(prim_path="/World/Looks/ballColorMaterial", color=np.asarray([0.0, 0.0, 1.0])) - physics_material = PhysicsMaterial( + sphere_geom = lazy.isaacsim.core.prims.SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) + visual_material = lazy.isaacsim.core.api.materials.preview_surface.PreviewSurface( + prim_path="/World/Looks/ballColorMaterial", color=np.asarray([0.0, 0.0, 1.0]) + ) + physics_material = lazy.isaacsim.core.api.materials.PhysicsMaterial( prim_path="/World/Looks/ballPhysicsMaterial", dynamic_friction=1.0, static_friction=0.2, @@ -166,7 +162,7 @@ def main(): # Set ball positions over terrain origins # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + ball_view = lazy.isaacsim.core.prims.RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) # cache initial state of the balls ball_initial_positions = terrain_importer.env_origins ball_initial_positions[:, 2] += 5.0 diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index 26bacac387c..81e489e546a 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -17,23 +17,21 @@ import trimesh from typing import Literal -import isaacsim.core.utils.prims as prim_utils import omni.kit import omni.kit.commands import pytest -from isaacsim.core.api.materials import PhysicsMaterial, PreviewSurface -from isaacsim.core.api.objects import DynamicSphere -from isaacsim.core.cloner import GridCloner -from isaacsim.core.prims import RigidPrim, SingleGeometryPrim, SingleRigidPrim -from isaacsim.core.utils.extensions import enable_extension from pxr import UsdGeom +import isaaclab.sim.utils.prims as prim_utils import isaaclab.terrains as terrain_gen +from isaaclab import lazy from isaaclab.sim import PreviewSurfaceCfg, SimulationContext, build_simulation_context, get_first_matching_child_prim from isaaclab.terrains import TerrainImporter, TerrainImporterCfg from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR +lazy.isaacsim.core.utils.extensions.enable_extension("omni.kit.primitive.mesh") + @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("env_spacing", [1.0, 4.325, 8.0]) @@ -174,7 +172,7 @@ def test_ball_drop(device): _populate_scene(geom_sphere=False, sim=sim) # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + ball_view = lazy.isaacsim.core.prims.RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) # Play simulator sim.reset() @@ -207,7 +205,7 @@ def test_ball_drop_geom_sphere(device): _populate_scene(geom_sphere=False, sim=sim) # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + ball_view = lazy.isaacsim.core.prims.RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) # Play simulator sim.reset() @@ -245,7 +243,7 @@ def _obtain_collision_mesh(mesh_prim_path: str, mesh_type: Literal["Mesh", "Plan def _obtain_grid_cloner_env_origins(num_envs: int, env_spacing: float, device: str) -> torch.Tensor: """Obtain the env origins generated by IsaacSim GridCloner (grid_cloner.py).""" # create grid cloner - cloner = GridCloner(spacing=env_spacing) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=env_spacing) cloner.define_base_env("/World/envs") envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs) prim_utils.define_prim("/World/envs/env_0") @@ -272,7 +270,7 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: terrain_importer = TerrainImporter(terrain_importer_cfg) # Create interface to clone the scene - cloner = GridCloner(spacing=2.0) + cloner = lazy.isaacsim.core.cloner.GridCloner(spacing=2.0) cloner.define_base_env("/World/envs") # Everything under the namespace "/World/envs/env_0" will be cloned prim_utils.define_prim(prim_path="/World/envs/env_0", prim_type="Xform") @@ -281,24 +279,26 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: # -- Ball if geom_sphere: # -- Ball physics - _ = DynamicSphere( + _ = lazy.isaacsim.core.objects.DynamicSphere( prim_path="/World/envs/env_0/ball", translation=np.array([0.0, 0.0, 5.0]), mass=0.5, radius=0.25 ) else: # -- Ball geometry - enable_extension("omni.kit.primitive.mesh") + lazy.isaacsim.core.utils.extensions.enable_extension("omni.kit.primitive.mesh") cube_prim_path = omni.kit.commands.execute("CreateMeshPrimCommand", prim_type="Sphere")[1] prim_utils.move_prim(cube_prim_path, "/World/envs/env_0/ball") # -- Ball physics - SingleRigidPrim( + lazy.isaacsim.core.prims.SingleRigidPrim( prim_path="/World/envs/env_0/ball", mass=0.5, scale=(0.5, 0.5, 0.5), translation=(0.0, 0.0, 0.5) ) - SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) + lazy.isaacsim.core.prims.SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) # -- Ball material - sphere_geom = SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) - visual_material = PreviewSurface(prim_path="/World/Looks/ballColorMaterial", color=np.asarray([0.0, 0.0, 1.0])) - physics_material = PhysicsMaterial( + sphere_geom = lazy.isaacsim.core.prims.SingleGeometryPrim(prim_path="/World/envs/env_0/ball", collision=True) + visual_material = lazy.isaacsim.core.api.materials.PreviewSurface( + prim_path="/World/Looks/ballColorMaterial", color=np.asarray([0.0, 0.0, 1.0]) + ) + physics_material = lazy.isaacsim.core.api.materials.PhysicsMaterial( prim_path="/World/Looks/ballPhysicsMaterial", dynamic_friction=1.0, static_friction=0.2, @@ -323,7 +323,7 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: # Set ball positions over terrain origins # Create a view over all the balls - ball_view = RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) + ball_view = lazy.isaacsim.core.prims.RigidPrim("/World/envs/env_.*/ball", reset_xform_properties=False) # cache initial state of the balls ball_initial_positions = terrain_importer.env_origins ball_initial_positions[:, 2] += 5.0 diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index 189f603864f..953bc04df3c 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -72,7 +72,7 @@ def get_camera_position(): try: from pxr import UsdGeom - from isaaclab.sim.utils import stage as stage_utils + import isaaclab.sim.utils.stage as stage_utils stage = stage_utils.get_current_stage() if stage is not None: diff --git a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py index d6a05d34bf4..7b0eeba281a 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py +++ b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py @@ -3,10 +3,9 @@ # # SPDX-License-Identifier: Apache-2.0 - import torch -from isaacsim.replicator.mobility_gen.impl.path_planner import compress_path, generate_paths +from isaaclab import lazy from .occupancy_map_utils import OccupancyMap from .scene_utils import HasPose2d @@ -197,11 +196,13 @@ def plan_path(start: HasPose2d, end: HasPose2d, occupancy_map: OccupancyMap) -> end_yx_pixels = end_xy_pixels[..., 0, ::-1] # Generate path using the mobility path planner - path_planner_output = generate_paths(start=start_yx_pixels, freespace=occupancy_map.freespace_mask()) + path_planner_output = lazy.isaacsim.replicator.mobility_gen.impl.path_planner.generate_paths( + start=start_yx_pixels, freespace=occupancy_map.freespace_mask() + ) # Extract and compress the path path_yx_pixels = path_planner_output.unroll_path(end_yx_pixels) - path_yx_pixels, _ = compress_path(path_yx_pixels) + path_yx_pixels, _ = lazy.isaacsim.replicator.mobility_gen.impl.path_planner.compress_path(path_yx_pixels) # Convert back from (y, x) to (x, y) format path_xy_pixels = path_yx_pixels[:, ::-1] diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py index 5b719b5efd1..2baf162ddbc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py @@ -7,10 +7,10 @@ import torch -from isaacsim.core.utils.torch.transformations import tf_combine, tf_inverse, tf_vector from pxr import UsdGeom import isaaclab.sim as sim_utils +from isaaclab import lazy from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg @@ -221,9 +221,11 @@ def get_env_local_pose(env_pos: torch.Tensor, xformable: UsdGeom.Xformable, devi finger_pose = torch.zeros(7, device=self.device) finger_pose[0:3] = (lfinger_pose[0:3] + rfinger_pose[0:3]) / 2.0 finger_pose[3:7] = lfinger_pose[3:7] - hand_pose_inv_rot, hand_pose_inv_pos = tf_inverse(hand_pose[3:7], hand_pose[0:3]) + hand_pose_inv_rot, hand_pose_inv_pos = lazy.isaacsim.core.utils.torch.transformations.tf_inverse( + hand_pose[3:7], hand_pose[0:3] + ) - robot_local_grasp_pose_rot, robot_local_pose_pos = tf_combine( + robot_local_grasp_pose_rot, robot_local_pose_pos = lazy.isaacsim.core.utils.torch.transformations.tf_combine( hand_pose_inv_rot, hand_pose_inv_pos, finger_pose[3:7], finger_pose[0:3] ) robot_local_pose_pos += torch.tensor([0, 0.04, 0], device=self.device) @@ -418,10 +420,10 @@ def _compute_rewards( dist_reward *= dist_reward dist_reward = torch.where(d <= 0.02, dist_reward * 2, dist_reward) - axis1 = tf_vector(franka_grasp_rot, gripper_forward_axis) - axis2 = tf_vector(drawer_grasp_rot, drawer_inward_axis) - axis3 = tf_vector(franka_grasp_rot, gripper_up_axis) - axis4 = tf_vector(drawer_grasp_rot, drawer_up_axis) + axis1 = lazy.isaacsim.core.utils.torch.transformations.tf_vector(franka_grasp_rot, gripper_forward_axis) + axis2 = lazy.isaacsim.core.utils.torch.transformations.tf_vector(drawer_grasp_rot, drawer_inward_axis) + axis3 = lazy.isaacsim.core.utils.torch.transformations.tf_vector(franka_grasp_rot, gripper_up_axis) + axis4 = lazy.isaacsim.core.utils.torch.transformations.tf_vector(drawer_grasp_rot, drawer_up_axis) dot1 = ( torch.bmm(axis1.view(num_envs, 1, 3), axis2.view(num_envs, 3, 1)).squeeze(-1).squeeze(-1) @@ -481,10 +483,10 @@ def _compute_grasp_transforms( drawer_local_grasp_rot, drawer_local_grasp_pos, ): - global_franka_rot, global_franka_pos = tf_combine( + global_franka_rot, global_franka_pos = lazy.isaacsim.core.utils.torch.transformations.tf_combine( hand_rot, hand_pos, franka_local_grasp_rot, franka_local_grasp_pos ) - global_drawer_rot, global_drawer_pos = tf_combine( + global_drawer_rot, global_drawer_pos = lazy.isaacsim.core.utils.torch.transformations.tf_combine( drawer_rot, drawer_pos, drawer_local_grasp_rot, drawer_local_grasp_pos ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py index a049354d3b4..3f229e67abc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/locomotion/locomotion_env.py @@ -7,10 +7,8 @@ import torch -import isaacsim.core.utils.torch as torch_utils -from isaacsim.core.utils.torch.rotations import compute_heading_and_up, compute_rot, quat_conjugate - import isaaclab.sim as sim_utils +from isaaclab import lazy from isaaclab.assets import Articulation from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg @@ -25,6 +23,12 @@ class LocomotionEnv(DirectRLEnv): def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs): super().__init__(cfg, render_mode, **kwargs) + self._compute_intermediate_values_fn = _make_compute_intermediate_values( + lazy.isaacsim.core.utils.torch.rotations.compute_heading_and_up, + lazy.isaacsim.core.utils.torch.rotations.compute_rot, + lazy.isaacsim.core.utils.torch.maths.unscale, + ) + self.action_scale = self.cfg.action_scale self.joint_gears = torch.tensor(self.cfg.joint_gears, dtype=torch.float32, device=self.sim.device) self.motor_effort_ratio = torch.ones_like(self.joint_gears, device=self.sim.device) @@ -41,7 +45,9 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs self.heading_vec = torch.tensor([1, 0, 0], dtype=torch.float32, device=self.sim.device).repeat( (self.num_envs, 1) ) - self.inv_start_rot = quat_conjugate(self.start_rotation).repeat((self.num_envs, 1)) + self.inv_start_rot = lazy.isaacsim.core.utils.torch.rotations.quat_conjugate(self.start_rotation).repeat( + (self.num_envs, 1) + ) self.basis_vec0 = self.heading_vec.clone() self.basis_vec1 = self.up_vec.clone() @@ -88,7 +94,7 @@ def _compute_intermediate_values(self): self.dof_pos_scaled, self.prev_potentials, self.potentials, - ) = compute_intermediate_values( + ) = self._compute_intermediate_values_fn( self.targets, self.torso_position, self.torso_rotation, @@ -228,53 +234,56 @@ def compute_rewards( return total_reward -@torch.jit.script -def compute_intermediate_values( - targets: torch.Tensor, - torso_position: torch.Tensor, - torso_rotation: torch.Tensor, - velocity: torch.Tensor, - ang_velocity: torch.Tensor, - dof_pos: torch.Tensor, - dof_lower_limits: torch.Tensor, - dof_upper_limits: torch.Tensor, - inv_start_rot: torch.Tensor, - basis_vec0: torch.Tensor, - basis_vec1: torch.Tensor, - potentials: torch.Tensor, - prev_potentials: torch.Tensor, - dt: float, -): - to_target = targets - torso_position - to_target[:, 2] = 0.0 +def _make_compute_intermediate_values(compute_heading_and_up_fn, compute_rot_fn, unscale_fn): + @torch.jit.script + def _compute_intermediate_values( + targets: torch.Tensor, + torso_position: torch.Tensor, + torso_rotation: torch.Tensor, + velocity: torch.Tensor, + ang_velocity: torch.Tensor, + dof_pos: torch.Tensor, + dof_lower_limits: torch.Tensor, + dof_upper_limits: torch.Tensor, + inv_start_rot: torch.Tensor, + basis_vec0: torch.Tensor, + basis_vec1: torch.Tensor, + potentials: torch.Tensor, + prev_potentials: torch.Tensor, + dt: float, + ): + to_target = targets - torso_position + to_target[:, 2] = 0.0 - torso_quat, up_proj, heading_proj, up_vec, heading_vec = compute_heading_and_up( - torso_rotation, inv_start_rot, to_target, basis_vec0, basis_vec1, 2 - ) + torso_quat, up_proj, heading_proj, up_vec, heading_vec = compute_heading_and_up_fn( + torso_rotation, inv_start_rot, to_target, basis_vec0, basis_vec1, 2 + ) - vel_loc, angvel_loc, roll, pitch, yaw, angle_to_target = compute_rot( - torso_quat, velocity, ang_velocity, targets, torso_position - ) + vel_loc, angvel_loc, roll, pitch, yaw, angle_to_target = compute_rot_fn( + torso_quat, velocity, ang_velocity, targets, torso_position + ) - dof_pos_scaled = torch_utils.maths.unscale(dof_pos, dof_lower_limits, dof_upper_limits) - - to_target = targets - torso_position - to_target[:, 2] = 0.0 - prev_potentials[:] = potentials - potentials = -torch.norm(to_target, p=2, dim=-1) / dt - - return ( - up_proj, - heading_proj, - up_vec, - heading_vec, - vel_loc, - angvel_loc, - roll, - pitch, - yaw, - angle_to_target, - dof_pos_scaled, - prev_potentials, - potentials, - ) + dof_pos_scaled = unscale_fn(dof_pos, dof_lower_limits, dof_upper_limits) + + to_target = targets - torso_position + to_target[:, 2] = 0.0 + prev_potentials[:] = potentials + potentials = -torch.norm(to_target, p=2, dim=-1) / dt + + return ( + up_proj, + heading_proj, + up_vec, + heading_vec, + vel_loc, + angvel_loc, + roll, + pitch, + yaw, + angle_to_target, + dof_pos_scaled, + prev_potentials, + potentials, + ) + + return _compute_intermediate_values diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/mdp/rewards.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/mdp/rewards.py index 0d14620e225..f1be9d3f3b2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/mdp/rewards.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/mdp/rewards.py @@ -8,8 +8,7 @@ import torch from typing import TYPE_CHECKING -from isaacsim.core.utils.torch.transformations import tf_combine - +from isaaclab import lazy from isaaclab.managers import SceneEntityCfg from isaaclab.sensors.frame_transformer.frame_transformer import FrameTransformer @@ -86,12 +85,12 @@ def compute_keypoint_distance( # Compute keypoints for current and target poses for idx, keypoint_offset in enumerate(keypoint_offsets): # Transform keypoint offset to world coordinates for current pose - keypoints_current[:, idx] = tf_combine( + keypoints_current[:, idx] = lazy.isaacsim.core.utils.torch.transformations.tf_combine( current_quat, current_pos, identity_quat, keypoint_offset.repeat(num_envs, 1) )[1] # Transform keypoint offset to world coordinates for target pose - keypoints_target[:, idx] = tf_combine( + keypoints_target[:, idx] = lazy.isaacsim.core.utils.torch.transformations.tf_combine( target_quat, target_pos, identity_quat, keypoint_offset.repeat(num_envs, 1) )[1] # Calculate L2 norm distance between corresponding keypoints diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py index f7b8e9db59b..0c9ed67b83b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/utils.py @@ -10,9 +10,9 @@ import trimesh from trimesh.sample import sample_surface -import isaacsim.core.utils.prims as prim_utils from pxr import UsdGeom +import isaaclab.sim.utils.prims as prim_utils from isaaclab.sim.utils import get_all_matching_child_prims # ---- module-scope caches ---- diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py index 009a44b1b37..7d9c20d6513 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/mdp/franka_stack_events.py @@ -11,9 +11,8 @@ import torch from typing import TYPE_CHECKING -from isaacsim.core.utils.extensions import enable_extension - import isaaclab.utils.math as math_utils +from isaaclab import lazy from isaaclab.assets import Articulation, AssetBase from isaaclab.managers import SceneEntityCfg @@ -274,7 +273,7 @@ def randomize_visual_texture_material( # textures = [default_texture] # enable replicator extension if not already enabled - enable_extension("omni.replicator.core") + lazy.isaacsim.core.utils.extensions.enable_extension("omni.replicator.core") # we import the module here since we may not always need the replicator import omni.replicator.core as rep diff --git a/source/isaaclab_tasks/test/benchmarking/env_benchmark_test_utils.py b/source/isaaclab_tasks/test/benchmarking/env_benchmark_test_utils.py index 0c939ca0166..65dda6aed64 100644 --- a/source/isaaclab_tasks/test/benchmarking/env_benchmark_test_utils.py +++ b/source/isaaclab_tasks/test/benchmarking/env_benchmark_test_utils.py @@ -150,9 +150,9 @@ def _retrieve_logs(workflow, task): """Retrieve training logs.""" # first grab all log files repo_path = os.path.join(carb.tokens.get_tokens_interface().resolve("${app}"), "..") - from isaacsim.core.version import get_version + from isaaclab import lazy - if int(get_version()[2]) < 5: + if int(lazy.isaacsim.core.version.get_version()[2]) < 5: repo_path = os.path.join(repo_path, "..") if workflow == "rl_games": log_files_path = os.path.join(repo_path, f"logs/{workflow}/{task}/*/summaries/*") diff --git a/source/isaaclab_tasks/test/env_test_utils.py b/source/isaaclab_tasks/test/env_test_utils.py index 1034fd9ac92..dded4056d41 100644 --- a/source/isaaclab_tasks/test/env_test_utils.py +++ b/source/isaaclab_tasks/test/env_test_utils.py @@ -13,8 +13,8 @@ import carb import omni.usd import pytest -from isaacsim.core.version import get_version +from isaaclab import lazy from isaaclab.envs.utils.spaces import sample_space from isaaclab_tasks.utils.parse_cfg import parse_env_cfg @@ -110,7 +110,7 @@ def _run_environments( """ # skip test if stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5 and create_stage_in_memory: pytest.skip("Stage in memory is not supported in this version of Isaac Sim") diff --git a/source/isaaclab_tasks/test/test_environments_with_stage_in_memory.py b/source/isaaclab_tasks/test/test_environments_with_stage_in_memory.py index 70dcf94961f..66297ad5299 100644 --- a/source/isaaclab_tasks/test/test_environments_with_stage_in_memory.py +++ b/source/isaaclab_tasks/test/test_environments_with_stage_in_memory.py @@ -12,14 +12,13 @@ if sys.platform != "win32": import pinocchio # noqa: F401 +from isaaclab import lazy from isaaclab.app import AppLauncher # launch the simulator app_launcher = AppLauncher(headless=True, enable_cameras=True) simulation_app = app_launcher.app -from isaacsim.core.version import get_version - """Rest everything follows.""" import pytest @@ -48,7 +47,7 @@ @pytest.mark.parametrize("task_name", setup_environment(include_play=False, factory_envs=False, multi_agent=False)) def test_environments_with_stage_in_memory_and_clone_in_fabric_disabled(task_name, num_envs, device): # skip test if stage in memory is not supported - isaac_sim_version = float(".".join(get_version()[2])) + isaac_sim_version = float(".".join(lazy.isaacsim.core.version.get_version()[2])) if isaac_sim_version < 5: pytest.skip("Stage in memory is not supported in this version of Isaac Sim")